diff --git a/AUTHORS.txt b/AUTHORS.txt
old mode 100644
new mode 100755
diff --git a/LICENSE.txt b/LICENSE.txt
old mode 100644
new mode 100755
diff --git a/README.md b/README.md
old mode 100644
new mode 100755
index e6dce6d..1bdb5e0
--- a/README.md
+++ b/README.md
@@ -1,3 +1,4 @@
+<<<<<<< HEAD
KN2C-Program
========
@@ -38,3 +39,8 @@ Faraz Fallahi (fffaraz@gmail.com)
Milad AbaieRad (milad.abaeirad@gmail.com )
Mohsen Raoufi (mohsen.raoufi.2007@gmail.com)
+
+
+=======
+# MergeTest
+>>>>>>> 28ea424bd019bb77bc1ab02977d2f91922110bed
diff --git a/autocompile.sh b/autocompile.sh
old mode 100644
new mode 100755
diff --git a/autorun.sh b/autorun.sh
old mode 100644
new mode 100755
diff --git a/config/settings.ini b/config/settings.ini
old mode 100644
new mode 100755
index 9bc3f3c..fa32789
--- a/config/settings.ini
+++ b/config/settings.ini
@@ -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
@@ -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]
@@ -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
diff --git a/config/vars.ini b/config/vars.ini
old mode 100644
new mode 100755
diff --git a/config/vars_sim.ini b/config/vars_sim.ini
old mode 100644
new mode 100755
diff --git a/old_code/skill/skillkick.cpp b/old_code/skill/skillkick.cpp
old mode 100644
new mode 100755
diff --git a/old_code/skill/skillkick.h b/old_code/skill/skillkick.h
old mode 100644
new mode 100755
diff --git a/old_code/tactic/tacticblock.cpp b/old_code/tactic/tacticblock.cpp
old mode 100644
new mode 100755
diff --git a/old_code/tactic/tacticblock.h b/old_code/tactic/tacticblock.h
old mode 100644
new mode 100755
diff --git a/old_code/tactic/tacticstop.cpp b/old_code/tactic/tacticstop.cpp
old mode 100644
new mode 100755
diff --git a/old_code/tactic/tacticstop.h b/old_code/tactic/tacticstop.h
old mode 100644
new mode 100755
diff --git a/src/3rdparty/fsa.h b/src/3rdparty/fsa.h
old mode 100644
new mode 100755
diff --git a/src/3rdparty/stlastar.h b/src/3rdparty/stlastar.h
old mode 100644
new mode 100755
diff --git a/src/ai/Skills.h b/src/ai/Skills.h
old mode 100644
new mode 100755
diff --git a/src/ai/Skills.h.autosave b/src/ai/Skills.h.autosave
new file mode 100755
index 0000000..7e8f8b9
--- /dev/null
+++ b/src/ai/Skills.h.autosave
@@ -0,0 +1,12 @@
+#ifndef SKILLS_H
+#define SKILLS_H
+
+#include "skill.h"
+#include "skill/skillkick.h"
+#include "skill/skilltest.h"
+#include "skill/skillonetouch.h"
+#include "skill/skillpassreceive.h"
+//seyed ali hejazi
+#include "skill/shootball.h"
+
+#endif // SKILLS_H
diff --git a/src/ai/agent.cpp b/src/ai/agent.cpp
index da5ebc0..e49032a 100644
--- a/src/ai/agent.cpp
+++ b/src/ai/agent.cpp
@@ -6,8 +6,6 @@ Agent::Agent() :
{
wm = 0;
id = -1;
-
- ctrl = new Controller();
}
void Agent::setID(int id)
@@ -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;
@@ -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;
}
+
diff --git a/src/ai/agent.h b/src/ai/agent.h
index 264b772..1919a2b 100644
--- a/src/ai/agent.h
+++ b/src/ai/agent.h
@@ -81,7 +81,7 @@ class Agent : public Robot
private:
int id;
- Controller *ctrl;
+ Controller ctrl;
Navigation nav;
OutputBuffer *outputBuffer;
WorldModel *wm;
diff --git a/src/ai/ai.cpp b/src/ai/ai.cpp
old mode 100644
new mode 100755
index 23ec217..bcf9492
--- a/src/ai/ai.cpp
+++ b/src/ai/ai.cpp
@@ -14,6 +14,9 @@
#include "play/playtest2.h"
#include "play/playlearning.h"
#include "play/playformations.h"
+//ali hejazi
+#include "play/playhw2_1.h"
+#include "play/mantomandefense.h"
AI::AI(WorldModel *worldmodel, QString field_size, OutputBuffer *outputbuffer, QObject *parent) :
QObject(parent),
@@ -21,6 +24,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);
diff --git a/src/ai/ai.h b/src/ai/ai.h
old mode 100644
new mode 100755
diff --git a/src/ai/knowledge.cpp b/src/ai/knowledge.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/knowledge.h b/src/ai/knowledge.h
old mode 100644
new mode 100755
diff --git a/src/ai/learning/hillclimbing.cpp b/src/ai/learning/hillclimbing.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/learning/hillclimbing.h b/src/ai/learning/hillclimbing.h
old mode 100644
new mode 100755
diff --git a/src/ai/learning/kick_learning.cpp b/src/ai/learning/kick_learning.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/learning/kick_learning.h b/src/ai/learning/kick_learning.h
old mode 100644
new mode 100755
diff --git a/src/ai/learning/policy.cpp b/src/ai/learning/policy.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/learning/policy.h b/src/ai/learning/policy.h
old mode 100644
new mode 100755
diff --git a/src/ai/learning/policyMem.proto b/src/ai/learning/policyMem.proto
old mode 100644
new mode 100755
diff --git a/src/ai/man2man.cpp b/src/ai/man2man.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/man2man.h b/src/ai/man2man.h
old mode 100644
new mode 100755
diff --git a/src/ai/mapsearchnode.cpp b/src/ai/mapsearchnode.cpp
old mode 100644
new mode 100755
index 9c87661..faee99a
--- a/src/ai/mapsearchnode.cpp
+++ b/src/ai/mapsearchnode.cpp
@@ -1,3 +1,4 @@
+
#include "mapsearchnode.h"
#include "worldmodel.h"
@@ -82,37 +83,102 @@ bool MapSearchNode::GetSuccessors(AStarSearch *astarsearch, MapSe
wm->navigation_pos.clear();
//kamin
- for(int i=0; inavigation_pos.append(node.vec);
+ //kamout
+ if(node.vec != parent) astarsearch->AddSuccessor(node);
+ }
+ }
+ }
+ else{
+ int goal_p_count=8;
+ for(int j=0; jnavigation_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;gnavigation_pos.append(node.vec);
+ //kamout
+ if(node.vec != parent) astarsearch->AddSuccessor(node);
+ }
}
}
}
+
+ //test
+// for(int i=obs.size()-2; inavigation_pos.append(node.vec);
+// //kamout
+// if(node.vec != parent) astarsearch->AddSuccessor(node);
+// }
+// }
+// }
+
+
+ //test
+
MapSearchNode goal;
goal.vec = astarsearch->GetSolutionEnd()->vec;
astarsearch->AddSuccessor(goal);
@@ -146,11 +212,8 @@ float MapSearchNode::GetCost(MapSearchNode &successor)
QList MapSearchNode::getObsCircle()
{
QList 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);
@@ -164,7 +227,7 @@ QList 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)
@@ -192,6 +255,15 @@ QList 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; ipredict_pos.size(); i++)
// {
// Circle2D c(wm->predict_pos[i], b_rad);
diff --git a/src/ai/mapsearchnode.h b/src/ai/mapsearchnode.h
old mode 100644
new mode 100755
diff --git a/src/ai/mwbm.cpp b/src/ai/mwbm.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/mwbm.h b/src/ai/mwbm.h
old mode 100644
new mode 100755
diff --git a/src/ai/navigation.cpp b/src/ai/navigation.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/navigation.h b/src/ai/navigation.h
old mode 100644
new mode 100755
diff --git a/src/ai/play.cpp b/src/ai/play.cpp
old mode 100644
new mode 100755
index 9270d7e..00ba943
--- a/src/ai/play.cpp
+++ b/src/ai/play.cpp
@@ -36,10 +36,9 @@ Tactic* Play::getTactic(int id)
if(id >= PLAYERS_MAX_NUM || id < 0) return NULL;
return tactics[id];
}
-
bool Play::conditionChanged()
{
- bool out;
+ bool out = true;
QList activeAgents=wm->kn->ActiveAgents();
if(activeAgents.size() != numberOfPlayers)
{
diff --git a/src/ai/play.h b/src/ai/play.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freeKicks.h b/src/ai/play/freeKicks/freeKicks.h
old mode 100644
new mode 100755
index b5020c3..1512737
--- a/src/ai/play/freeKicks/freeKicks.h
+++ b/src/ai/play/freeKicks/freeKicks.h
@@ -14,7 +14,11 @@
#include "freekick10.h"
#include "freekick11.h"
#include "freekick47.h"
-
+//armin sadreddin
+#include "freekicktest1.h"
+//armin sadreddin
#include "freekickdirect.h"
-
+//kamran
+#include"freekicktest2.h"
+//kamran
#endif // FREEKICKS_H
diff --git a/src/ai/play/freeKicks/freekick1.cpp b/src/ai/play/freeKicks/freekick1.cpp
old mode 100644
new mode 100755
index e218580..b3ddf53
--- a/src/ai/play/freeKicks/freekick1.cpp
+++ b/src/ai/play/freeKicks/freekick1.cpp
@@ -176,7 +176,7 @@ void freeKick1::execute()
activeAgents.removeOne(tAttackerMid->getID());
if(wm->cmgs.ourIndirectKick())
{
- // recieverID = tAttackerMid->findBestPlayerForPass();
+ recieverID = tAttackerMid->findBestPlayerForPass();
if(recieverID != -1)
{
wm->ourRobot[recieverID].Status = AgentStatus::RecievingPass;
diff --git a/src/ai/play/freeKicks/freekick1.h b/src/ai/play/freeKicks/freekick1.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick10.cpp b/src/ai/play/freeKicks/freekick10.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick10.h b/src/ai/play/freeKicks/freekick10.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick11.cpp b/src/ai/play/freeKicks/freekick11.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick11.h b/src/ai/play/freeKicks/freekick11.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick2.cpp b/src/ai/play/freeKicks/freekick2.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick2.h b/src/ai/play/freeKicks/freekick2.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick3.cpp b/src/ai/play/freeKicks/freekick3.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick3.h b/src/ai/play/freeKicks/freekick3.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick4.cpp b/src/ai/play/freeKicks/freekick4.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick4.h b/src/ai/play/freeKicks/freekick4.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick47.cpp b/src/ai/play/freeKicks/freekick47.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick47.h b/src/ai/play/freeKicks/freekick47.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick5.cpp b/src/ai/play/freeKicks/freekick5.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick5.h b/src/ai/play/freeKicks/freekick5.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick6.cpp b/src/ai/play/freeKicks/freekick6.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick6.h b/src/ai/play/freeKicks/freekick6.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick7.cpp b/src/ai/play/freeKicks/freekick7.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick7.h b/src/ai/play/freeKicks/freekick7.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick8.cpp b/src/ai/play/freeKicks/freekick8.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick8.h b/src/ai/play/freeKicks/freekick8.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick9.cpp b/src/ai/play/freeKicks/freekick9.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick9.h b/src/ai/play/freeKicks/freekick9.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick_base.cpp b/src/ai/play/freeKicks/freekick_base.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekick_base.h b/src/ai/play/freeKicks/freekick_base.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekickdirect.cpp b/src/ai/play/freeKicks/freekickdirect.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekickdirect.h b/src/ai/play/freeKicks/freekickdirect.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/freeKicks/freekicktest1.cpp b/src/ai/play/freeKicks/freekicktest1.cpp
new file mode 100644
index 0000000..341e8be
--- /dev/null
+++ b/src/ai/play/freeKicks/freekicktest1.cpp
@@ -0,0 +1,190 @@
+#include "freekicktest1.h"
+
+freekicktest1::freekicktest1(WorldModel *worldmodel, QObject *parent) :
+ freeKick_base(worldmodel,parent)
+{
+ freeKickStart = false;
+ freeKickRegion = fkRegion::RightRegion;
+ oppLevel = Level::Beginner;
+}
+
+int freekicktest1::enterCondition(Level level)
+{
+ if( wm->kn->IsInsideRect(wm->ball.pos.loc, Vector2D(0.44*Field::MaxX,Field::MaxY)
+ , Vector2D(Field::MaxX,0.82*Field::MaxY))
+ ||
+ wm->kn->IsInsideRect(wm->ball.pos.loc, Vector2D(0.44*Field::MaxX,0.82*Field::MinY)
+ , Vector2D(Field::MaxX,Field::MinY)))
+ {
+ if( level == this->oppLevel)
+ return 600;
+ else
+ return 300;
+ }
+
+ return 0;
+}
+
+void freekicktest1::resetValues()
+{
+ this->rolesIsInit = false;
+}
+
+void freekicktest1::setPositions()
+{
+ Position leftDefPos,rightDefPos,goaliePos;
+ int leftID = -1, rightID = -1 , midID = -1;
+ bool leftNav, rightNav;
+
+ if( wm->ourRobot[previousLeftID].Role != AgentRole::DefenderLeft )
+ previousLeftID = -1;
+
+ if( wm->ourRobot[previousRightID].Role != AgentRole::DefenderRight )
+ previousRightID = -1;
+
+ if( (wm->ourRobot[tDefenderLeft->getID()].Role == AgentRole::DefenderLeft) && (leftChecker < PresenceCounter) )
+ {
+ leftID = tDefenderLeft->getID();
+ this->previousLeftID = tDefenderLeft->getID();;
+ }
+
+ if( wm->ourRobot[tDefenderRight->getID()].Role == AgentRole::DefenderRight && (rightChecker < PresenceCounter) )
+ {
+ rightID = tDefenderRight->getID();
+ this->previousRightID = tDefenderRight->getID();;
+ }
+
+ if( leftChecker > PresenceCounter || leftID == -1 || !wm->kn->robotIsIdle(leftID))
+ {
+ midID = rightID;
+ leftID = -1;
+ }
+
+ if( rightChecker > PresenceCounter || rightID == -1 || !wm->kn->robotIsIdle(rightID))
+ {
+ midID = leftID;
+ rightID = -1;
+ }
+
+ zonePositions(leftID,rightID,midID,goaliePos,leftDefPos,leftNav,rightDefPos,rightNav);
+
+ tDefenderLeft->setIdlePosition(leftDefPos);
+ tDefenderLeft->setUseNav(leftNav);
+ tDefenderRight->setIdlePosition(rightDefPos);
+ tDefenderRight->setUseNav(rightNav);
+
+ if( leftID != -1)
+ {
+ if( (wm->kn->robotIsIdle(leftID)) && (wm->ourRobot[leftID].pos.loc - leftDefPos.loc).length() > 250 )
+ leftChecker++;
+ else
+ leftChecker = 0;
+ }
+ else
+ {
+ if( !haltedRobotIsInField(previousLeftID) )
+ leftChecker = 0;
+ }
+
+ if( rightID != -1)
+ {
+ if( (wm->kn->robotIsIdle(rightID)) && (wm->ourRobot[rightID].pos.loc - rightDefPos.loc).length() > 250 )
+ rightChecker++;
+ else
+ rightChecker = 0;
+ }
+ else
+ {
+ if( !haltedRobotIsInField(previousRightID) )
+ rightChecker = 0;
+ }
+
+ tGolie->setIdlePosition(goaliePos);
+
+ Position left,right;
+ if( wm->ball.pos.loc.y < 0 )
+ {
+ left.loc = Vector2D(Field::MaxX/3,wm->ball.pos.loc.y+200);
+ right.loc = Vector2D(Field::MaxX/3,Field::oppGoalCenter.y+400);
+ }
+ else
+ {
+ left.loc = Vector2D(Field::MaxX/3,wm->ball.pos.loc.y-200);
+ right.loc = Vector2D(Field::MaxX/3,Field::oppGoalCenter.y-400);
+ }
+
+ left.dir = ( Field::oppGoalCenter - wm->ourRobot[tAttackerLeft->getID()].pos.loc).dir().radian();
+ tAttackerLeft->setIdlePosition(left);
+
+ right.dir = ( Field::oppGoalCenter - wm->ourRobot[tAttackerRight->getID()].pos.loc).dir().radian();
+ tAttackerRight->setIdlePosition(right);
+
+ leftPos = left;
+ rightPos = right;
+
+ tAttackerMid->setIdlePosition(wm->ourRobot[tAttackerMid->getID()].pos);
+
+ if( checkDistances() )
+ {
+ recieverID = tAttackerMid->findBestPlayerForPass();
+ tAttackerMid->youHavePermissionForKick(recieverID);
+ }
+ else
+ {
+ tAttackerMid->youDontHavePermissionForKick();
+ recieverID = -1;
+ }
+}
+
+bool freekicktest1::checkDistances()
+{
+ bool leftInPos = true , rightInPos = true;
+
+ if( wm->ourRobot[tAttackerLeft->getID()].isValid && tAttackerLeft->getID() != -1)
+ {
+ //if( !wm->kn->ReachedToPos(wm->ourRobot[tAttackerLeft->getID()].pos.loc, Vector2D(Field::MaxX/3,Field::oppGoalPost_L.y+200), 200))
+ if( (wm->ourRobot[tAttackerLeft->getID()].pos.loc - leftPos.loc).length() > 200)
+ leftInPos = false;
+ }
+
+ if( wm->ourRobot[tAttackerRight->getID()].isValid && tAttackerRight->getID() != -1)
+ {
+ // if( !wm->kn->ReachedToPos(wm->ourRobot[tAttackerRight->getID()].pos.loc, Vector2D(Field::MaxX/3,Field::oppGoalPost_R.y-200),200) )
+ if( (wm->ourRobot[tAttackerRight->getID()].pos.loc - rightPos.loc).length() > 200)
+ rightInPos = false;
+ }
+
+ return (rightInPos && leftInPos);
+}
+
+void freekicktest1::execute()
+{
+ QList activeAgents=wm->kn->ActiveAgents();
+
+ // if(!rolesIsInit)
+ initRole();
+
+ for(int i=0;iisKicker();
+ tAttackerMid->setFreeKickType(kickType::FreeKickTest1);
+
+ activeAgents.removeOne(tAttackerMid->getID());
+ if(wm->cmgs.ourIndirectKick())
+ {
+ // recieverID = tAttackerMid->findBestPlayerForPass();
+ if(recieverID != -1)
+ {
+ wm->ourRobot[recieverID].Status = AgentStatus::RecievingPass;
+ activeAgents.removeOne(recieverID);
+ }
+ }
+ while(activeAgents.size() > 0)
+ {
+ wm->ourRobot[activeAgents.takeFirst()].Status = AgentStatus::Idle;
+ }
+}
diff --git a/src/ai/play/freeKicks/freekicktest1.h b/src/ai/play/freeKicks/freekicktest1.h
new file mode 100644
index 0000000..98f0358
--- /dev/null
+++ b/src/ai/play/freeKicks/freekicktest1.h
@@ -0,0 +1,22 @@
+#ifndef FREEKICKTEST1_H
+#define FREEKICKTEST1_H
+
+#include "freekick_base.h"
+
+class freekicktest1 : public freeKick_base
+{
+public:
+ explicit freekicktest1(WorldModel *worldmodel, QObject *parent = 0);
+ virtual void execute();
+ virtual int enterCondition(Level level);
+ virtual void resetValues();
+
+private:
+ void setPositions();
+ bool checkDistances();
+
+ int recieverID;
+ Position rightPos, leftPos;
+};
+
+#endif // FREEKICKTEST1_H
diff --git a/src/ai/play/freeKicks/freekicktest2.cpp b/src/ai/play/freeKicks/freekicktest2.cpp
new file mode 100644
index 0000000..387ce6a
--- /dev/null
+++ b/src/ai/play/freeKicks/freekicktest2.cpp
@@ -0,0 +1,168 @@
+#include "freekicktest2.h"
+freeKickTest2::freeKickTest2(WorldModel *worldmodel, QObject *parent) :
+ freeKick_base(worldmodel,parent)
+{
+ freeKickStart = false;
+ freeKickRegion = fkRegion::RightRegion;
+ oppLevel = Level::Beginner;
+}
+
+int freeKickTest2::enterCondition(Level level)
+{
+ if(wm->kn->IsInsideRect(wm->ball.pos.loc,Vector2D(Field::MinX,Field::MaxY),Vector2D(0,Field::MinY))){
+ if(oppLevel==level)
+ return 700;
+ else
+ return 100;
+ }
+}
+void freeKickTest2::resetValues()
+{
+ this->rolesIsInit = false;
+}
+
+void freeKickTest2::setPositions()
+{
+ Position leftDefPos,rightDefPos,goaliePos;
+ int leftID = -1, rightID = -1 , midID = -1;
+ bool leftNav, rightNav;
+
+ if( wm->ourRobot[previousLeftID].Role != AgentRole::DefenderLeft )
+ previousLeftID = -1;
+
+ if( wm->ourRobot[previousRightID].Role != AgentRole::DefenderRight )
+ previousRightID = -1;
+
+ if( (wm->ourRobot[tDefenderLeft->getID()].Role == AgentRole::DefenderLeft) && (leftChecker < PresenceCounter) )
+ {
+ leftID = tDefenderLeft->getID();
+ this->previousLeftID = tDefenderLeft->getID();;
+ }
+
+ if( wm->ourRobot[tDefenderRight->getID()].Role == AgentRole::DefenderRight && (rightChecker < PresenceCounter) )
+ {
+ rightID = tDefenderRight->getID();
+ this->previousRightID = tDefenderRight->getID();;
+ }
+
+ if( leftChecker > PresenceCounter || leftID == -1 || !wm->kn->robotIsIdle(leftID))
+ {
+ midID = rightID;
+ leftID = -1;
+ }
+
+ if( rightChecker > PresenceCounter || rightID == -1 || !wm->kn->robotIsIdle(rightID))
+ {
+ midID = leftID;
+ rightID = -1;
+ }
+
+ zonePositions(leftID,rightID,midID,goaliePos,leftDefPos,leftNav,rightDefPos,rightNav);
+
+ tDefenderLeft->setIdlePosition(leftDefPos);
+ tDefenderLeft->setUseNav(leftNav);
+ tDefenderRight->setIdlePosition(rightDefPos);
+ tDefenderRight->setUseNav(rightNav);
+
+ if( leftID != -1)
+ {
+ if( (wm->kn->robotIsIdle(leftID)) && (wm->ourRobot[leftID].pos.loc - leftDefPos.loc).length() > 250 )
+ leftChecker++;
+ else
+ leftChecker = 0;
+ }
+ else
+ {
+ if( !haltedRobotIsInField(previousLeftID) )
+ leftChecker = 0;
+ }
+
+ if( rightID != -1)
+ {
+ if( (wm->kn->robotIsIdle(rightID)) && (wm->ourRobot[rightID].pos.loc - rightDefPos.loc).length() > 250 )
+ rightChecker++;
+ else
+ rightChecker = 0;
+ }
+ else
+ {
+ if( !haltedRobotIsInField(previousRightID) )
+ rightChecker = 0;
+ }
+
+ tGolie->setIdlePosition(goaliePos);
+ Position leftAttacker,rightAttacker;
+ tAttackerMid->setIdlePosition(wm->ourRobot[tAttackerMid->getID()].pos);
+ int indexMax=maxOppThreshold();
+ int indexMin=minOppThreshold();
+ leftAttacker.loc=Vector2D(Field::MaxX*0.5,wm->ourRobot[indexMax].pos.loc.y);
+ rightAttacker.loc=Vector2D(Field::MaxX*0.5,wm->ourRobot[indexMin].pos.loc.y);
+ leftAttacker.dir=(Field::oppGoalCenter-wm->ourRobot[tAttackerLeft->getID()].pos.loc).dir().radian();
+ rightAttacker.dir=(Field::oppGoalCenter-wm->ourRobot[tAttackerRight->getID()].pos.loc).dir().radian();
+ leftPos=leftAttacker;
+ rightPos=rightAttacker;
+ if(checkDistances()){
+ recieverID=tAttackerMid->findBestPlayerForPass();
+ tAttackerMid->youHavePermissionForKick(recieverID);
+ }
+ else {
+ recieverID=-1;
+ tAttackerMid->youDontHavePermissionForKick();
+ }
+}
+int freeKickTest2::maxOppThreshold(){
+ int index;
+ double max=0;
+ QList oppAgent=wm->kn->ActiveOppAgents();
+ for(int i=0;iourRobot[oppAgent.at(i)].pos.loc.y){
+ max=wm->ourRobot[oppAgent.at(i)].pos.loc.y;
+ index=oppAgent.at(i);
+ }
+ }
+ return index;
+}
+
+int freeKickTest2::minOppThreshold(){
+ int index;
+ double min;
+ QList oppAgent=wm->kn->ActiveOppAgents();
+ min=oppAgent.at(0);
+ for(int i=0;iwm->ourRobot[oppAgent.at(i)].pos.loc.y){
+ min=wm->ourRobot[oppAgent.at(i)].pos.loc.y;
+ index=oppAgent.at(i);
+ }
+ }
+ return index;
+}
+
+bool freeKickTest2::checkDistances()
+{
+ bool value=false;
+ if(tAttackerRight->getID()!=-1 && tAttackerLeft->getID()!=-1 && !wm->ourRobot[tAttackerLeft->getID()].isValid && !wm->ourRobot[tAttackerRight->getID()].isValid)
+ if((wm->ourRobot[tAttackerLeft->getID()].pos.loc.y-leftPos.loc.y)<200 && (wm->ourRobot[tAttackerRight->getID()].pos.loc.y-rightPos.loc.y)<200){
+ value=true;
+ }
+ return value;
+}
+
+void freeKickTest2::execute()
+{
+ QList activeAgent=wm->kn->ActiveAgents();
+ for(int i=0;iisKicker(recieverID);
+ tAttackerMid->setFreeKickType(kickType::FreekickTest2);
+ activeAgent.removeOne(tAttackerMid->getID());
+ if(wm->cmgs.ourIndirectKick()){
+ if(recieverID!=-1){
+ wm->ourRobot[recieverID].Status=AgentStatus::RecievingPass;
+ activeAgent.removeOne(recieverID);
+ }
+ }
+ while(activeAgent.size()>0){
+ wm->ourRobot[activeAgent.takeFirst()].Status=AgentStatus::Idle;
+ }
+}
diff --git a/src/ai/play/freeKicks/freekicktest2.h b/src/ai/play/freeKicks/freekicktest2.h
new file mode 100644
index 0000000..338d625
--- /dev/null
+++ b/src/ai/play/freeKicks/freekicktest2.h
@@ -0,0 +1,22 @@
+#ifndef FREEKICKTEST2_H
+#define FREEKICKTEST2_H
+#include"freekick_base.h"
+class freeKickTest2 : public freeKick_base
+{
+public:
+ explicit freeKickTest2(WorldModel *worldmodel, QObject *parent = 0);
+ virtual void execute();
+ virtual int enterCondition(Level level);
+ virtual void resetValues();
+
+private:
+ void setPositions();
+ bool checkDistances();
+ int maxOppThreshold();
+ int minOppThreshold();
+ int recieverID;
+ Position rightPos, leftPos;
+
+};
+
+#endif // FREEKICKTEST2_H
diff --git a/src/ai/play/freeKicks/freekicktest3.cpp b/src/ai/play/freeKicks/freekicktest3.cpp
new file mode 100644
index 0000000..2609dbf
--- /dev/null
+++ b/src/ai/play/freeKicks/freekicktest3.cpp
@@ -0,0 +1,191 @@
+#include "freekicktest3.h"
+#include "freekick1.h"
+
+freeKick1::freeKick1(WorldModel *worldmodel, QObject *parent) :
+ freeKick_base(worldmodel,parent)
+{
+ freeKickStart = false;
+ freeKickRegion = fkRegion::RightRegion;
+ oppLevel = Level::Beginner;
+}
+
+int freeKick1::enterCondition(Level level)
+{
+ if( wm->kn->IsInsideRect(wm->ball.pos.loc, Vector2D(0.44*Field::MaxX,Field::MaxY)
+ , Vector2D(Field::MaxX,0.82*Field::MaxY))
+ ||
+ wm->kn->IsInsideRect(wm->ball.pos.loc, Vector2D(0.44*Field::MaxX,0.82*Field::MinY)
+ , Vector2D(Field::MaxX,Field::MinY)))
+ {
+ if( level == this->oppLevel)
+ return 600;
+ else
+ return 300;
+ }
+
+ return 0;
+}
+
+void freeKick1::resetValues()
+{
+ this->rolesIsInit = false;
+}
+
+void freeKick1::setPositions()
+{
+ Position leftDefPos,rightDefPos,goaliePos;
+ int leftID = -1, rightID = -1 , midID = -1;
+ bool leftNav, rightNav;
+
+ if( wm->ourRobot[previousLeftID].Role != AgentRole::DefenderLeft )
+ previousLeftID = -1;
+
+ if( wm->ourRobot[previousRightID].Role != AgentRole::DefenderRight )
+ previousRightID = -1;
+
+ if( (wm->ourRobot[tDefenderLeft->getID()].Role == AgentRole::DefenderLeft) && (leftChecker < PresenceCounter) )
+ {
+ leftID = tDefenderLeft->getID();
+ this->previousLeftID = tDefenderLeft->getID();;
+ }
+
+ if( wm->ourRobot[tDefenderRight->getID()].Role == AgentRole::DefenderRight && (rightChecker < PresenceCounter) )
+ {
+ rightID = tDefenderRight->getID();
+ this->previousRightID = tDefenderRight->getID();;
+ }
+
+ if( leftChecker > PresenceCounter || leftID == -1 || !wm->kn->robotIsIdle(leftID))
+ {
+ midID = rightID;
+ leftID = -1;
+ }
+
+ if( rightChecker > PresenceCounter || rightID == -1 || !wm->kn->robotIsIdle(rightID))
+ {
+ midID = leftID;
+ rightID = -1;
+ }
+
+ zonePositions(leftID,rightID,midID,goaliePos,leftDefPos,leftNav,rightDefPos,rightNav);
+
+ tDefenderLeft->setIdlePosition(leftDefPos);
+ tDefenderLeft->setUseNav(leftNav);
+ tDefenderRight->setIdlePosition(rightDefPos);
+ tDefenderRight->setUseNav(rightNav);
+
+ if( leftID != -1)
+ {
+ if( (wm->kn->robotIsIdle(leftID)) && (wm->ourRobot[leftID].pos.loc - leftDefPos.loc).length() > 250 )
+ leftChecker++;
+ else
+ leftChecker = 0;
+ }
+ else
+ {
+ if( !haltedRobotIsInField(previousLeftID) )
+ leftChecker = 0;
+ }
+
+ if( rightID != -1)
+ {
+ if( (wm->kn->robotIsIdle(rightID)) && (wm->ourRobot[rightID].pos.loc - rightDefPos.loc).length() > 250 )
+ rightChecker++;
+ else
+ rightChecker = 0;
+ }
+ else
+ {
+ if( !haltedRobotIsInField(previousRightID) )
+ rightChecker = 0;
+ }
+
+ tGolie->setIdlePosition(goaliePos);
+
+ Position left,right;
+ if( wm->ball.pos.loc.y < 0 )
+ {
+ left.loc = Vector2D(Field::MaxX/3,wm->ball.pos.loc.y+200);
+ right.loc = Vector2D(Field::MaxX/3,Field::oppGoalCenter.y+400);
+ }
+ else
+ {
+ left.loc = Vector2D(Field::MaxX/3,wm->ball.pos.loc.y-200);
+ right.loc = Vector2D(Field::MaxX/3,Field::oppGoalCenter.y-400);
+ }
+
+ left.dir = ( Field::oppGoalCenter - wm->ourRobot[tAttackerLeft->getID()].pos.loc).dir().radian();
+ tAttackerLeft->setIdlePosition(left);
+
+ right.dir = ( Field::oppGoalCenter - wm->ourRobot[tAttackerRight->getID()].pos.loc).dir().radian();
+ tAttackerRight->setIdlePosition(right);
+
+ leftPos = left;
+ rightPos = right;
+
+ tAttackerMid->setIdlePosition(wm->ourRobot[tAttackerMid->getID()].pos);
+
+ if( checkDistances() )
+ {
+ recieverID = tAttackerMid->findBestPlayerForPass();
+ tAttackerMid->youHavePermissionForKick(recieverID);
+ }
+ else
+ {
+ tAttackerMid->youDontHavePermissionForKick();
+ recieverID = -1;
+ }
+}
+
+bool freeKick1::checkDistances()
+{
+ bool leftInPos = true , rightInPos = true;
+
+ if( wm->ourRobot[tAttackerLeft->getID()].isValid && tAttackerLeft->getID() != -1)
+ {
+ //if( !wm->kn->ReachedToPos(wm->ourRobot[tAttackerLeft->getID()].pos.loc, Vector2D(Field::MaxX/3,Field::oppGoalPost_L.y+200), 200))
+ if( (wm->ourRobot[tAttackerLeft->getID()].pos.loc - leftPos.loc).length() > 200)
+ leftInPos = false;
+ }
+
+ if( wm->ourRobot[tAttackerRight->getID()].isValid && tAttackerRight->getID() != -1)
+ {
+ // if( !wm->kn->ReachedToPos(wm->ourRobot[tAttackerRight->getID()].pos.loc, Vector2D(Field::MaxX/3,Field::oppGoalPost_R.y-200),200) )
+ if( (wm->ourRobot[tAttackerRight->getID()].pos.loc - rightPos.loc).length() > 200)
+ rightInPos = false;
+ }
+
+ return (rightInPos && leftInPos);
+}
+
+void freeKick1::execute()
+{
+ QList activeAgents=wm->kn->ActiveAgents();
+
+ // if(!rolesIsInit)
+ initRole();
+
+ for(int i=0;iisKicker();
+ tAttackerMid->setFreeKickType(kickType::FreeKick1);
+
+ activeAgents.removeOne(tAttackerMid->getID());
+ if(wm->cmgs.ourIndirectKick())
+ {
+ recieverID = tAttackerMid->findBestPlayerForPass();
+ if(recieverID != -1)
+ {
+ wm->ourRobot[recieverID].Status = AgentStatus::RecievingPass;
+ activeAgents.removeOne(recieverID);
+ }
+ }
+ while(activeAgents.size() > 0)
+ {
+ wm->ourRobot[activeAgents.takeFirst()].Status = AgentStatus::Idle;
+ }
+}
diff --git a/src/ai/play/mantomandefense.cpp b/src/ai/play/mantomandefense.cpp
new file mode 100755
index 0000000..8b3b2a9
--- /dev/null
+++ b/src/ai/play/mantomandefense.cpp
@@ -0,0 +1,59 @@
+#include "mantomandefense.h"
+
+mantomanDefense::mantomanDefense(WorldModel *worldmodel, QObject *parent) :
+ Play("PlayTest", worldmodel, parent)
+{
+
+}
+
+int mantomanDefense::enterCondition()
+{
+ return 0;
+}
+
+void mantomanDefense::initRole()
+{
+}
+
+void mantomanDefense::execute()
+{
+
+ QList diffender = wm->kn->ActiveAgents();
+ QList enemy = wm->kn->ActiveOppAgents();
+ QList > distances;
+ for(int i = diffender.length() ; i > 0 ; i--){
+ AlgorithmMin(diffender,enemy);
+ }
+}
+
+void mantomanDefense::AlgorithmMin(QList& enm,QList& ally){
+ QList > distances;
+ for(int i = 0 ; i < ally.length() ; i++){
+ QList dists;
+ for(int j = 0 ; j < enm.length() ; j++){
+ Segment2D seg(wm->ourRobot[ally[i]].pos.loc,wm->oppRobot[enm[j]].pos.loc);
+ std::cout << "i am here" << std::endl;
+ dists.append(seg.length());
+ }
+ distances.append(dists);
+ }
+
+ double min = 99999999;
+ int minIndex1 = 0;
+ int minIndex2 = 0;
+ for(int i = 0 ; i < ally.length() ; i++){
+ for(int j = 0 ; j < enm.length() ; j++){
+ if(distances[i][j] < min){
+ min = distances[i][j];
+ minIndex1 = i;
+ minIndex2 = j;
+ }
+ }
+ }
+ tacticmantoman = new TacticTestStandingForwardEnemy(wm);
+ tacticmantoman->setDistance(4);
+ tacticmantoman->setOppRobotIndex(enm[minIndex2]);
+ tactics[ally[minIndex1]] = tacticmantoman;
+ ally.removeAt(minIndex1);
+ enm.removeAt(minIndex2);
+}
diff --git a/src/ai/play/mantomandefense.h b/src/ai/play/mantomandefense.h
new file mode 100755
index 0000000..3a544e4
--- /dev/null
+++ b/src/ai/play/mantomandefense.h
@@ -0,0 +1,19 @@
+#ifndef MANTOMANDEFENSE_H
+#define MANTOMANDEFENSE_H
+#include "play.h"
+#include "man2man.h"
+
+class mantomanDefense : public Play
+{
+ Q_OBJECT
+public:
+ explicit mantomanDefense(WorldModel *worldmodel, QObject *parent = 0);
+ virtual void execute();
+ virtual void initRole();
+ virtual int enterCondition();
+private:
+ TacticTestStandingForwardEnemy* tacticmantoman;
+ void AlgorithmMin(QList& enm, QList& ally);
+};
+
+#endif // MANTOMANDEFENSE_H
diff --git a/src/ai/play/playcontrol.cpp b/src/ai/play/playcontrol.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/playcontrol.h b/src/ai/play/playcontrol.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/playformations.cpp b/src/ai/play/playformations.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/playformations.h b/src/ai/play/playformations.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/playfreekickopp.cpp b/src/ai/play/playfreekickopp.cpp
old mode 100644
new mode 100755
index cd79d9e..0015bf8
--- a/src/ai/play/playfreekickopp.cpp
+++ b/src/ai/play/playfreekickopp.cpp
@@ -3,27 +3,17 @@
PlayFreeKickOpp::PlayFreeKickOpp(WorldModel *worldmodel, QObject *parent) :
Play("PlayFreeKickOpp", worldmodel, parent)
{
- numberOfPlayers = 0;
-
- rolesIsInit = false;
- go2ThePositions = false;
-
- waitTimer = new QTimer();
- connect(waitTimer,SIGNAL(timeout()),this,SLOT(waitTimer_timout()));
-
- tGolie = new TacticGoalie(wm);
-
- tDefenderLeft = new TacticDefender(wm);
- tDefenderRight = new TacticDefender(wm);
-
- tAttackerLeft = new TacticAttacker(wm);
- tAttackerMid = new TacticAttacker(wm);
- tAttackerRight = new TacticAttacker(wm);
+ tGolie=new TacticGoalie(wm);
+ tDefenderLeft=new TacticDefender(wm);
+ tDefenderRight=new TacticDefender(wm);
+ tAttackerLeft=new TacticAttacker(wm);
+ tAttackerMid=new TacticAttacker(wm);
+ tAttackerRight=new TacticAttacker(wm);
}
int PlayFreeKickOpp::enterCondition()
{
- if(wm->cmgs.theirFreeKick() || wm->cmgs.theirDirectKick())
+ /*if(wm->cmgs.theirFreeKick() || wm->cmgs.theirDirectKick())
{
if(wm->gs_last != wm->gs)
{
@@ -41,134 +31,146 @@ int PlayFreeKickOpp::enterCondition()
else
{
return 0;
- }
- // return 200000;
+ }*/
+ return 0;
}
-
-void PlayFreeKickOpp::waitTimer_timout()
-{
- waitTimer->stop();
- go2ThePositions = true;
-}
-
void PlayFreeKickOpp::initRole()
{
- QList activeAgents=wm->kn->ActiveAgents();
- numberOfPlayers = activeAgents.size();
- activeAgents.removeOne(wm->ref_goalie_our);
- wm->ourRobot[wm->ref_goalie_our].Role = AgentRole::Golie;
- switch (activeAgents.length()) {
+ QList ourActivePlayer=wm->kn->ActiveAgents();
+ ourActivePlayer.removeOne(wm->ref_goalie_our);
+ wm->ourRobot[wm->ref_goalie_our].Role=AgentRole::Golie;
+ switch(ourActivePlayer.length()){
case 1:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::AttackerLeft;
break;
case 2:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::AttackerLeft;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::AttackerRight;
break;
case 3:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerMid;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::DefenderRight;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::DefenderLeft;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::AttackerLeft;
break;
case 4:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerMid;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerLeft;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::DefenderRight;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::DefenderLeft;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::AttackerLeft;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::AttackerMid;
break;
case 5:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerMid;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerRight;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::DefenderRight;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::DefenderLeft;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::AttackerLeft;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::AttackerMid;
+ wm->ourRobot[ourActivePlayer.takeFirst()].Role=AgentRole::AttackerRight;
break;
}
- rolesIsInit = true;
}
-void PlayFreeKickOpp::pressing()
-{
- QList oppPlayers = wm->kn->ActiveOppAgents();
- QList oppInSecure;
- oppPlayers.removeOne(wm->ref_goalie_opp);
-
- QList ourPlayers = wm->kn->findAttackers();
- ourPlayers.removeOne(wm->ref_goalie_our);
-
- int counter = 0;
- while( counter < oppPlayers.size() )
- {
- if( wm->kn->IsInsideSecureArea(wm->oppRobot[oppPlayers.at(counter)].pos.loc,wm->ball.pos.loc))
- {
- oppInSecure.append(oppPlayers.at(counter));
- oppPlayers.removeAt(counter);
+bool PlayFreeKickOpp::isInsideTriangle(Vector2D pos, Vector2D vertex1){
+ bool firstCon=false;
+ bool secondCon=false;
+ if((vertex1.x-Field::ourGoalPost_L.x)!=0 && pos.y<(vertex1.y-Field::ourGoalPost_L.y)/(vertex1.x-Field::ourGoalPost_L.x)*(pos.x-vertex1.x)+vertex1.y)
+ firstCon=true;
+ if((vertex1.x-Field::ourGoalPost_R.x)!=0 && pos.y>(vertex1.y-Field::ourGoalPost_R.y)/(vertex1.x-Field::ourGoalPost_R.x)*(pos.x-vertex1.x)+vertex1.y)
+ secondCon=true;
+ return firstCon && secondCon;
+}
+QList PlayFreeKickOpp::findmarking(Position_Evaluation posEval[],int oppNum){
+ double temp;
+ int tempID;
+ QList man2man;
+ for(int i=0;ikn->IsInsideFarArea(wm->oppRobot[oppPlayers.at(counter)].pos.loc) )
- oppPlayers.removeAt(counter);
- else
- counter++;
}
-
- // if( wm->cmgs.theirDirectKick() && oppInSecure.size() == 1 )
- // oppPlayers.append(oppInSecure.first() );
-
- Marking defence;
- defence.setWorldModel(wm);
- bool isMatched;
- QList m2m = defence.findMarking(ourPlayers,oppPlayers,isMatched);
- if( isMatched )
- {
- for(int i=0;ioppID=posEval[0].id;
+ man2man.at(0)->ourID=tAttackerLeft->getID();
+ man2man.at(1)->oppID=posEval[1].id;
+ man2man.at(1)->ourID=tAttackerRight->getID();
+ if(posEval[2].score==posEval[1].score){
+ man2man.append(new marking_player);
+ man2man.at(2)->oppID=posEval[2].id;
+ man2man.at(2)->ourID=tDefenderLeft->getID();
}
+ return man2man;
+}
- while ( ourPlayers.size() > 0 )
- {
- wm->ourRobot[ourPlayers.takeFirst()].Status = AgentStatus::Idle;
- }
-
- wm->marking = m2m;
-
- if( wm->cmgs.theirDirectKick() && wm->defenceMode)
- {
- wm->ourRobot[tDefenderLeft->getID()].Status = AgentStatus::BlockingBall;
- wm->ourRobot[tDefenderRight->getID()].Status = AgentStatus::BlockingBall;
- }
+void PlayFreeKickOpp::pressing()
+{
+ QList oppPlayer=wm->kn->ActiveOppAgents();
+ QList ourPlayer=wm->kn->ActiveAgents();
+ oppPlayer.removeOne(wm->ref_goalie_opp);
+ ourPlayer.removeOne(wm->ref_goalie_our);
+ int count=0;
+ Position_Evaluation posEval[oppPlayer.length()];
+ //find distance to goal and ball
+ for(int i=0;ioppRobot[oppPlayer.at(i)].pos.loc.dist(Field::ourGoalCenter);
+ posEval[i].ballDis=wm->oppRobot[oppPlayer.at(i)].pos.loc.dist(wm->ball.pos.loc);
+ posEval[i].id=oppPlayer.at(i);
+ }
+ for(int i=0;ioppRobot[oppPlayer.at(i)].pos.loc,Field::ourGoalPost_L);
+ Segment2D segment2(wm->oppRobot[oppPlayer.at(i)].pos.loc,Field::ourGoalPost_R);
+ posEval[i].goalAngle=abs(segment1.direction().radian()-segment2.direction().radian());
+ for(int j=0;joppRobot[ourPlayer.at(j)].pos.loc,wm->ourRobot[ourPlayer.at(i)].pos.loc))
+ count++;
+ }
+ posEval[i].count=count;
+ }
+ for(int i=0;ioppRobot[posEval[i].id].pos.loc.x>0)
+ posEval[i].score=-1*(1/posEval[i].ballDis)+(10/posEval[i].goalDis);
+ if(wm->oppRobot[posEval[i].id].pos.loc.x<0)
+ posEval[i].score=(1/posEval[i].ballDis)+(10/posEval[i].goalDis);
+ }
+ else if(count>1)
+ posEval[i].score=0;
+ }
+ for(int i=0;iourID,man2man.at(i)->oppID);
+ }
}
-void PlayFreeKickOpp::setTactics(int index)
+void PlayFreeKickOpp::setTactics(int RobotID)
{
- switch (wm->ourRobot[index].Role) {
- case AgentRole::Golie:
- tactics[index] = tGolie;
- break;
- case AgentRole::DefenderLeft:
- tactics[index] = tDefenderLeft;
- break;
- case AgentRole::DefenderRight:
- tactics[index] = tDefenderRight;
+ switch(wm->ourRobot[RobotID].Role){
+ case AgentRole::AttackerLeft:
+ tactics[RobotID]=tAttackerLeft;
break;
case AgentRole::AttackerMid:
- tactics[index] = tAttackerMid;
+ tactics[RobotID]=tAttackerMid;
break;
case AgentRole::AttackerRight:
- tactics[index] = tAttackerRight;
+ tactics[RobotID]=tAttackerRight;
break;
- case AgentRole::AttackerLeft:
- tactics[index] = tAttackerLeft;
+ case AgentRole::DefenderLeft:
+ tactics[RobotID]=tDefenderLeft;
break;
- default:
+ case AgentRole::DefenderRight:
+ tactics[RobotID]=tDefenderRight;
+ break;
+ case AgentRole::Golie:
+ tactics[RobotID]=tGolie;
break;
}
}
@@ -197,17 +199,11 @@ void PlayFreeKickOpp::setPositions()
this->previousRightID = tDefenderRight->getID();;
}
- if( leftChecker > PresenceCounter || leftID == -1 || !wm->kn->robotIsIdle(leftID))
- {
+ if( leftChecker > PresenceCounter || leftID == -1 )
midID = rightID;
- leftID = -1;
- }
- if( rightChecker > PresenceCounter || rightID == -1 || !wm->kn->robotIsIdle(rightID))
- {
+ if( rightChecker > PresenceCounter || rightID == -1)
midID = leftID;
- rightID = -1;
- }
zonePositions(leftID,rightID,midID,goaliePos,leftDefPos,leftNav,rightDefPos,rightNav);
@@ -218,7 +214,7 @@ void PlayFreeKickOpp::setPositions()
if( leftID != -1)
{
- if( (wm->kn->robotIsIdle(leftID)) && (wm->ourRobot[leftID].pos.loc - leftDefPos.loc).length() > 250 )
+ if( (wm->ourRobot[leftID].Status != AgentStatus::FollowingBall ) && (wm->ourRobot[leftID].pos.loc - leftDefPos.loc).length() > 250 )
leftChecker++;
else
leftChecker = 0;
@@ -231,7 +227,7 @@ void PlayFreeKickOpp::setPositions()
if( rightID != -1)
{
- if( (wm->kn->robotIsIdle(rightID)) && (wm->ourRobot[rightID].pos.loc - rightDefPos.loc).length() > 250 )
+ if( (wm->ourRobot[rightID].Status != AgentStatus::FollowingBall ) && (wm->ourRobot[rightID].pos.loc - rightDefPos.loc).length() > 250 )
rightChecker++;
else
rightChecker = 0;
@@ -243,151 +239,119 @@ void PlayFreeKickOpp::setPositions()
}
tGolie->setIdlePosition(goaliePos);
-
- Vector2D finalPos,notImportant,leftPos,rightPos;
-
- Circle2D robotCircle(wm->ball.pos.loc,ALLOW_NEAR_BALL_RANGE);
- Segment2D line2Goal(wm->ball.pos.loc,Field::ourGoalCenter);
- robotCircle.intersection(line2Goal,&finalPos,¬Important);
-
- Circle2D secondCircle(finalPos,(2.5)*ROBOT_RADIUS);
- robotCircle.intersection(secondCircle,&leftPos,&rightPos);
-
- if( !wm->kn->IsInsideField(leftPos) )
- {
- leftPos = finalPos;
- finalPos = rightPos;
-
- Vector2D leftPos2,rightPos2;
- Circle2D secondCircle(finalPos,(2.5)*ROBOT_RADIUS);
- robotCircle.intersection(secondCircle,&leftPos2,&rightPos2);
-
- if( leftPos.dist(leftPos2) < leftPos.dist(rightPos2) )
- rightPos = rightPos2;
- else
- rightPos = leftPos2;
-
+ if(man2man.length()==3){
+ Position attackerRight,attackerLeft,defenderLeft;
+ Vector2D inter1,inter2;
+ Circle2D circle1(wm->oppRobot[man2man.at(1)->oppID].pos.loc,50);
+ Segment2D seg1(wm->oppRobot[man2man.at(1)->oppID].pos.loc,Field::ourGoalCenter);
+ circle1.intersection(seg1,&inter1,&inter2);
+ tAttackerRight->setIdlePosition(inter1);
+ Vector2D inter3,inter4;
+ Circle2D circle2(wm->oppRobot[man2man.at(0)->oppID].pos.loc,50);
+ Segment2D seg2(wm->oppRobot[man2man.at(0)->oppID].pos.loc,Field::ourGoalCenter);
+ circle2.intersection(seg2,&inter3,&inter4);
+ tAttackerLeft->setIdlePosition(inter3);
+ Vector2D inter5,inter6;
+ Circle2D circle3(wm->oppRobot[man2man.at(2)->oppID].pos.loc,50);
+ Segment2D seg3(wm->oppRobot[man2man.at(2)->oppID].pos.loc,Field::ourGoalCenter);
+ circle3.intersection(seg3,&inter5,&inter6);
+ tDefenderLeft->setIdlePosition(inter5);
+ /* attackerRight.loc=wm->oppRobot[man2man.at(1)->oppID].pos.loc+threshhold;
+ attackerRight.dir=wm->oppRobot[man2man.at(1)->oppID].pos.dir+AngleDeg::PI;
+ tAttackerRight->setIdlePosition(attackerRight);
+ attackerLeft.loc=wm->oppRobot[man2man.at(0)->oppID].pos.loc+threshhold;
+ attackerLeft.dir=wm->oppRobot[man2man.at(0)->oppID].pos.dir+AngleDeg::PI;
+ tAttackerLeft->setIdlePosition(attackerLeft);
+ defenderLeft.loc=wm->oppRobot[man2man.at(2)->oppID].pos.loc+threshhold;
+ defenderLeft.dir=wm->oppRobot[man2man.at(2)->oppID].pos.dir+AngleDeg::PI;
+ tDefenderLeft->setIdlePosition(attackerLeft);*/
}
- else if( !wm->kn->IsInsideField(rightPos) )
- {
- rightPos = finalPos;
- finalPos = leftPos;
-
- Vector2D leftPos2,rightPos2;
- Circle2D secondCircle(finalPos,(2.5)*ROBOT_RADIUS);
- robotCircle.intersection(secondCircle,&leftPos2,&rightPos2);
+ else if(man2man.length()==2){
+ Vector2D inter1,inter2;
+ Circle2D circle1(wm->oppRobot[man2man.at(1)->oppID].pos.loc,50);
+ Segment2D seg1(wm->oppRobot[man2man.at(1)->oppID].pos.loc,Field::ourGoalCenter);
+ circle1.intersection(seg1,&inter1,&inter2);
+ tAttackerRight->setIdlePosition(inter1);
+ Vector2D inter3,inter4;
+ Circle2D circle2(wm->oppRobot[man2man.at(0)->oppID].pos.loc,50);
+ Segment2D seg2(wm->oppRobot[man2man.at(0)->oppID].pos.loc,Field::ourGoalCenter);
+ circle2.intersection(seg2,&inter3,&inter4);
+ tAttackerLeft->setIdlePosition(inter3);
+ }
+ int kickerId;
+ QList oppPlayer=wm->kn->ActiveOppAgents();
+ double minDist=wm->oppRobot[oppPlayer.at(0)].pos.loc.dist(wm->ball.pos.loc);
+ for(int i=0;iwm->oppRobot[oppPlayer.at(i)].pos.loc.dist(wm->ball.pos.loc)){
+ minDist=wm->oppRobot[oppPlayer.at(i)].pos.loc.dist(wm->ball.pos.loc);
+ kickerId=oppPlayer.at(i);
+ }
+ }
+ Vector2D inter1,inter2;
+ Line2D seg(wm->ball.pos.loc,wm->oppRobot[kickerId].pos.loc);
+ Circle2D circle(wm->ball.pos.loc,200);
+ circle.intersection(seg,&inter1,&inter2);
+ if(inter1.xsetIdlePosition(inter1);
+ else if(inter1.x>inter2.x)
+ tAttackerMid->setIdlePosition(inter2);
- if( rightPos.dist(leftPos2) < rightPos.dist(rightPos2) )
- leftPos = rightPos2;
- else
- leftPos = leftPos2;
+}
+TacticAttacker* PlayFreeKickOpp::findTacticAttacker(int RobotID){
+ if(wm->ourRobot[RobotID].Role==AgentRole::AttackerLeft){
+ leftAttacker=false;
+ return tAttackerLeft;
}
-
- QList pointsForIdle;
-
- if( wm->kn->IsInsideNearArea(wm->ball.pos.loc) )
- {
- Vector2D candidateL_1, candidateL_2, mainL;
-
- Circle2D cir_l(Field::defenceLineLinear_L,Field::goalCircle_R+ROBOT_RADIUS);
- Line2D thirty_l(Field::defenceLineLinear_L,AngleDeg(0));
- cir_l.intersection(thirty_l,&candidateL_1,&candidateL_2);
- if( wm->kn->IsInsideField(candidateL_1) && !wm->kn->IsInsideGolieArea(candidateL_1) )
- mainL = candidateL_1;
- else
- mainL = candidateL_2;
-
- pointsForIdle.append(Vector2D(mainL.x, -sign(wm->ball.pos.loc.y)*mainL.y));
-
- pointsForIdle.append(Vector2D(Field::ourPenaltySpot.x+200,Field::ourPenaltySpot.y));
-
- // pointsForIdle.append(Vector2D(mainL.x, sign(wm->ball.pos.loc.y)*mainL.y));
+ else if(wm->ourRobot[RobotID].Role==AgentRole::AttackerRight){
+ rightAttacker=false;
+ return tAttackerRight;
}
-
- pointsForIdle.append(finalPos);
- pointsForIdle.append(rightPos);
- pointsForIdle.append(leftPos);
-
- if(tAttackerLeft->getID()!=-1 && wm->ourRobot[tAttackerLeft->getID()].isValid && wm->ourRobot[tAttackerLeft->getID()].Status==AgentStatus::Idle)
- {
- for(int i=0;ikn->isOccupied(tAttackerLeft->getID(),pointsForIdle.at(i)))
- {
- tAttackerLeft->setIdlePosition(pointsForIdle.at(i));
- break;
- }
- }
-
+ else if(wm->ourRobot[RobotID].Role==AgentRole::AttackerMid){
+ midAttacker=false;
+ return tAttackerMid;
}
-
- if(tAttackerRight->getID()!=-1 && wm->ourRobot[tAttackerRight->getID()].isValid && wm->ourRobot[tAttackerRight->getID()].Status==AgentStatus::Idle)
- {
- for(int i=0;ikn->isOccupied(tAttackerRight->getID(),pointsForIdle.at(i)))
- {
- tAttackerRight->setIdlePosition(pointsForIdle.at(i));
- break;
- }
- }
-
+ return 0;
+}
+TacticDefender* PlayFreeKickOpp::findTacticDefender(int RobotID){
+ if(wm->ourRobot[RobotID].Role==AgentRole::DefenderLeft){
+ leftDefender=false;
+ return tDefenderLeft;
}
-
- if(tAttackerMid->getID()!=-1 && wm->ourRobot[tAttackerMid->getID()].isValid && wm->ourRobot[tAttackerMid->getID()].Status==AgentStatus::Idle)
- {
- for(int i=0;ikn->isOccupied(tAttackerMid->getID(),pointsForIdle.at(i)))
- {
- tAttackerMid->setIdlePosition(pointsForIdle.at(i));
- break;
- }
- }
-
+ else if(wm->ourRobot[RobotID].Role==AgentRole::DefenderRight){
+ rightDefender=false;
+ return tDefenderRight;
}
+ return 0;
}
void PlayFreeKickOpp::setPlayer2Keep(int ourR, int oppR)
{
- wm->ourRobot[ourR].Status = AgentStatus::BlockingRobot;
-
- switch (wm->ourRobot[ourR].Role)
- {
- case AgentRole::AttackerMid:
- tAttackerMid->setPlayerToKeep(oppR);
- break;
- case AgentRole::AttackerRight:
- tAttackerRight->setPlayerToKeep(oppR);
- break;
- case AgentRole::AttackerLeft:
- tAttackerLeft->setPlayerToKeep(oppR);
- break;
+ switch(wm->ourRobot[ourR].Role){
case AgentRole::DefenderLeft:
tDefenderLeft->setPlayerToKeep(oppR);
break;
case AgentRole::DefenderRight:
tDefenderRight->setPlayerToKeep(oppR);
break;
- default:
+ case AgentRole::AttackerLeft:
+ tAttackerRight->setPlayerToKeep(oppR);
+ case AgentRole::AttackerRight:
+ tAttackerRight->setPlayerToKeep(oppR);
break;
}
}
void PlayFreeKickOpp::execute()
{
- if(go2ThePositions)
- {
- QList activeAgents=wm->kn->ActiveAgents();
-
- // if( !rolesIsInit )
- initRole();
- // else
- pressing();
-
- for(int i=0;i ourActivePlayer=wm->kn->ActiveAgents();
+ for(int i=0;iourRobot[ourActivePlayer.at(i)].Status=AgentStatus::Idle;
+ }
+ initRole();
+ for(int i=0;i
+struct Position_Evaluation{
+ double goalAngle;
+ int count;
+ int id;
+ double goalDis;
+ double ballDis;
+ double score;
+};
+struct marking_player{
+ int ourID;
+ int oppID;
+};
class PlayFreeKickOpp : public Play
{
@@ -10,24 +23,20 @@ class PlayFreeKickOpp : public Play
public:
explicit PlayFreeKickOpp(WorldModel *worldmodel, QObject *parent = 0);
virtual void execute();
- //virtual Tactic* getTactic(int id);
virtual int enterCondition();
private:
- bool go2ThePositions;
-
TacticGoalie* tGolie;
TacticDefender* tDefenderLeft;
+ bool leftDefender=true;
TacticDefender* tDefenderRight;
+ bool rightDefender=true;
TacticAttacker* tAttackerMid;
+ bool midAttacker=true;
TacticAttacker* tAttackerLeft;
+ bool leftAttacker=true;
TacticAttacker* tAttackerRight;
-
- QTimer *waitTimer;
-
-private slots:
- void waitTimer_timout();
-
+ bool rightAttacker=true;
protected:
virtual void initRole();
@@ -36,6 +45,12 @@ private slots:
void setTactics(int index);
void setPositions();
void setPlayer2Keep(int ourR,int oppR);
+ TacticAttacker* findTacticAttacker(int RobotID);
+ TacticDefender* findTacticDefender(int RobotID);
+ bool isInsideTriangle(Vector2D pos,Vector2D vertex1);
+ QListfindmarking(Position_Evaluation posEval[],int oppNum);
+ QListman2man;
+
};
#endif // PLAYFREEKICKOPP_H
diff --git a/src/ai/play/playfreekickour.cpp b/src/ai/play/playfreekickour.cpp
old mode 100644
new mode 100755
index 6bbf9eb..b6d1bf0
--- a/src/ai/play/playfreekickour.cpp
+++ b/src/ai/play/playfreekickour.cpp
@@ -81,6 +81,17 @@ void PlayFreeKickOur::execute()
if( wm->select_fk[11] )
fk.append(new freeKick11(wm));
+ if(wm->select_fk[12])
+ fk.append(new freeKickTest2(wm));
+ wm->select_fk[12]=true;
+
+ if( wm->select_fk[12] )
+ fk.append(new freekicktest1(wm));
+ wm->select_fk[12]=true;
+
+ if( wm->select_fk[13] )
+ fk.append(new freekicktest1(wm));
+
if( wm->select_fk[NUMBEROFFREEKICKS-1] )
fk.append(new freeKick47(wm));
diff --git a/src/ai/play/playfreekickour.h b/src/ai/play/playfreekickour.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/playgameon.cpp b/src/ai/play/playgameon.cpp
old mode 100644
new mode 100755
index e573966..79be99c
--- a/src/ai/play/playgameon.cpp
+++ b/src/ai/play/playgameon.cpp
@@ -102,13 +102,13 @@ void PlayGameOn::pressing(int ballOwner)
wm->marking = m2m;
}
-int PlayGameOn::findBallOwner()
+int PlayGameOn::findBallOwner() // I was here
{
int ownerIndex = -1;
QList candidates , ours = wm->kn->ActiveAgents();
QList distance2Prediction;
- if( wm->ball.isValid && !wm->kn->IsInsideGolieArea(wm->ball.pos.loc) )
+ if( wm->ball.isValid && !wm->kn->IsInsideGolieArea(wm->ball.pos.loc) ) // agar toop valid bud va dakhele mohavate nabud
{
if( wm->defenceMode )
candidates = wm->kn->findAttackers();
@@ -281,7 +281,6 @@ QList PlayGameOn::freeRegions()
void PlayGameOn::initRole()
{
wm->marking.clear();
-
QList activeAgents=wm->kn->ActiveAgents();
QList attackers;
numberOfPlayers = activeAgents.size();
@@ -303,6 +302,7 @@ void PlayGameOn::initRole()
activeAgents.removeAt(i);
}
}
+
int counter = 0;
while( counter < activeAgents.size() )
{
@@ -445,7 +445,7 @@ void PlayGameOn::coach()
}
tGolie->setIdlePosition(goaliePos);
-
+ wm->debug_pos.append(goaliePos.loc);//test
game_status = wm->kn->gameStatus(game_status);
int ballOwner = findBallOwner();
diff --git a/src/ai/play/playgameon.h b/src/ai/play/playgameon.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/playhalt.cpp b/src/ai/play/playhalt.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/playhalt.h b/src/ai/play/playhalt.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/playhw2_1.cpp b/src/ai/play/playhw2_1.cpp
new file mode 100755
index 0000000..b5b6e2b
--- /dev/null
+++ b/src/ai/play/playhw2_1.cpp
@@ -0,0 +1,23 @@
+#include "playhw2_1.h"
+
+PlayHW2_1::PlayHW2_1(WorldModel *worldmodel, QObject *parent) :
+ Play("PlayTest", worldmodel, parent)
+{
+ tTest = new TacticTestStandingForwardEnemy(wm);
+}
+
+int PlayHW2_1::enterCondition()
+{
+ return 0;
+}
+
+void PlayHW2_1::initRole()
+{
+}
+
+void PlayHW2_1::execute()
+{
+ tTest->setDistance(5);
+ tactics[wm->kn->ActiveAgents()[0]] = tTest;
+
+}
diff --git a/src/ai/play/playhw2_1.h b/src/ai/play/playhw2_1.h
new file mode 100755
index 0000000..589e98a
--- /dev/null
+++ b/src/ai/play/playhw2_1.h
@@ -0,0 +1,20 @@
+#ifndef PLAYHW2_1_H
+#define PLAYHW2_1_H
+#include "play.h"
+#include "man2man.h"
+#include "tactic/tacticteststandingforwardenemy.h"
+
+class PlayHW2_1 : public Play
+{
+
+ Q_OBJECT
+public:
+ explicit PlayHW2_1(WorldModel *worldmodel, QObject *parent = 0);
+ virtual void execute();
+ virtual void initRole();
+ virtual int enterCondition();
+private:
+ TacticTestStandingForwardEnemy* tTest;
+};
+
+#endif // PLAYHW2_1_H
diff --git a/src/ai/play/playkickoffopp.cpp b/src/ai/play/playkickoffopp.cpp
old mode 100644
new mode 100755
index 3e09df0..c215517
--- a/src/ai/play/playkickoffopp.cpp
+++ b/src/ai/play/playkickoffopp.cpp
@@ -1,248 +1,303 @@
#include "playkickoffopp.h"
-
+#include
+#include
+#include
PlayKickoffOpp::PlayKickoffOpp(WorldModel *worldmodel, QObject *parent) :
Play("PlayKickoffOpp", worldmodel, parent)
{
tGolie=new TacticGoalie(wm);
-
+ tAttackerLeft=new TacticAttacker(wm);
+ tAttackerMid=new TacticAttacker(wm);
+ tAttackerRight=new TacticAttacker(wm);
tDefenderLeft=new TacticDefender(wm);
tDefenderRight=new TacticDefender(wm);
- tAttackerLeft = new TacticAttacker(wm);
- tAttackerMid = new TacticAttacker(wm);
- tAttackerRight = new TacticAttacker(wm);
}
int PlayKickoffOpp::enterCondition()
{
- if(wm->cmgs.theirKickoff())
+ /*if(wm->cmgs.theirKickoff())
return 100;
else
- return 0;
+ return 0;*/
+ return 9999;
}
void PlayKickoffOpp::initRole()
{
- QList activeAgents=wm->kn->ActiveAgents();
- numberOfPlayers = activeAgents.size();
- activeAgents.removeOne(wm->ref_goalie_our);
- wm->ourRobot[wm->ref_goalie_our].Role = AgentRole::Golie;
- switch (activeAgents.length()) {
- case 1:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerMid;
- break;
- case 2:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
- break;
- case 3:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerMid;
- break;
- case 4:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerMid;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerLeft;
- break;
- case 5:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerMid;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerLeft;
- break;
+ QList ourCurrentPlayers=wm->kn->ActiveAgents();
+ ourCurrentPlayers.removeOne(wm->ref_goalie_our);
+ wm->ourRobot[wm->ref_goalie_our].Role=AgentRole::Golie;
+ switch(ourCurrentPlayers.length()){
+ case 1:
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::DefenderLeft;
+ break;
+ case 2:
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::DefenderLeft;
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::DefenderRight;
+ break;
+ case 3:
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::DefenderLeft;
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::DefenderRight;
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::AttackerMid;
+ break;
+ case 4:
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::DefenderLeft;
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::DefenderRight;
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::AttackerMid;
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::AttackerLeft;
+ break;
+ case 5:
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::DefenderLeft;
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::DefenderRight;
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::AttackerMid;
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::AttackerLeft;
+ wm->ourRobot[ourCurrentPlayers.takeFirst()].Role=AgentRole::AttackerRight;
+ break;
+
}
}
-
void PlayKickoffOpp::setTactics(int index)
{
- switch (wm->ourRobot[index].Role) {
- case AgentRole::Golie:
- tactics[index] = tGolie;
- break;
- case AgentRole::DefenderLeft:
- tactics[index] = tDefenderLeft;
- break;
- case AgentRole::DefenderRight:
- tactics[index] = tDefenderRight;
- break;
- case AgentRole::AttackerMid:
- tactics[index] = tAttackerMid;
- break;
- case AgentRole::AttackerRight:
- tactics[index] = tAttackerRight;
- break;
- case AgentRole::AttackerLeft:
- tactics[index] = tAttackerLeft;
- break;
- default:
- break;
+ switch(wm->ourRobot[index].Role){
+ case AgentRole::Golie:
+ tactics[index]=tGolie;
+ break;
+ case AgentRole::AttackerLeft:
+ tactics[index]=tAttackerLeft;
+ break;
+ case AgentRole::AttackerMid:
+ tactics[index]=tAttackerMid;
+ break;
+ case AgentRole::AttackerRight:
+ tactics[index]=tAttackerRight;
+ break;
+ case AgentRole::DefenderLeft:
+ tactics[index]=tDefenderLeft;
+ break;
+ case AgentRole::DefenderRight:
+ tactics[index]=tDefenderRight;
+ break;
+ }
+}
+int PlayKickoffOpp::maximumGoalChanceID(QList oppPlayer){
+ QList ourPlayer=wm->kn->ActiveAgents();
+ QList RobotTriangle;
+ ourPlayer.removeOne(wm->ref_goalie_our);
+ ourPlayer.removeOne(tAttackerMid->getID());
+ ourPlayer.removeOne(tAttackerRight->getID());
+ oppPlayer.removeOne(wm->ref_goalie_opp);
+ oppPlayer.removeOne(kickerId);
+ double maxAngle=0;
+ int count=0;
+ int maxCount=0;
+ int maxId;
+ for(int i=0;ioppRobot[oppPlayer.at(i)].pos.loc,Field::ourGoalPost_L);
+ Segment2D segment2(wm->oppRobot[oppPlayer.at(i)].pos.loc,Field::ourGoalPost_R);
+ for(int j=0;jourRobot[ourPlayer.at(j)].pos.loc,wm->oppRobot[oppPlayer.at(i)].pos.loc)){
+ RobotTriangle.append(ourPlayer.at(j));
+ }
+ }
+ for(int y=Field::ourGoalPost_R.y;yoppRobot[oppPlayer.at(i)].pos.loc,loc);
+ bool value=true;
+ for(int j=0;jourRobot[RobotTriangle.at(j)].pos.loc,ROBOT_RADIUS);
+ Vector2D inter1,inter2;
+ circle.intersection(seg,&inter1,&inter2);
+ if((inter1.x!=0 && inter1.y!=0) || (inter2.x!=0 && inter2.y!=0))
+ value=false;
+ }
+ if(value)
+ count++;
+ }
+ if(/*maxAngle(vertex1.y-Field::ourGoalPost_R.y)/(vertex1.x-Field::ourGoalPost_R.x)*(pos.x-vertex1.x)+vertex1.y)
+ secondCon=true;
+ return firstCon && secondCon;
+}
+Position PlayKickoffOpp::KickerPositioning(Vector2D oppKicker){
+ Line2D line(wm->ball.pos.loc,oppKicker);
+ Circle2D circle(wm->ball.pos.loc,oppKicker.dist(wm->ball.pos.loc));
+ Vector2D firstIntersect,secondIntersect;
+ Position pos;
+ circle.intersection(line,&firstIntersect,&secondIntersect);
+ if(firstIntersect!=oppKicker)
+ pos.loc=firstIntersect;
+ else if(secondIntersect!=oppKicker)
+ pos.loc=secondIntersect;
+ pos.dir=oppKicker.dir().radian()*-1;
+ return pos;
+}
+void PlayKickoffOpp::findOppKickerId(){
+ QList oppPlayer=wm->kn->ActiveOppAgents();
+ double minDist=wm->oppRobot[oppPlayer.at(0)].pos.loc.dist(wm->ball.pos.loc);
+ for(int i=0;iwm->oppRobot[oppPlayer.at(i)].pos.loc.dist(wm->ball.pos.loc)){
+ minDist=wm->oppRobot[oppPlayer.at(i)].pos.loc.dist(wm->ball.pos.loc);
+ kickerId=oppPlayer.at(i);
+ }
}
}
-void PlayKickoffOpp::setPositions()
-{
- Position leftDefPos,rightDefPos,goaliePos;
- int leftID = -1, rightID = -1 , midID = -1;
- bool leftNav, rightNav;
-
- if( wm->ourRobot[tDefenderLeft->getID()].Role == AgentRole::DefenderLeft )
- leftID = tDefenderLeft->getID();
-
- if( wm->ourRobot[tDefenderRight->getID()].Role == AgentRole::DefenderRight )
- rightID = tDefenderRight->getID();
-
- if( leftChecker > 100 || leftID == -1 )
- midID = rightID;
-
- if( rightChecker > 100 || rightID == -1)
- midID = leftID;
-
- zonePositions(leftID,rightID,midID,goaliePos,leftDefPos,leftNav,rightDefPos,rightNav);
-
- tGolie->setIdlePosition(goaliePos);
- tDefenderLeft->setIdlePosition(leftDefPos);
- tDefenderLeft->setUseNav(leftNav);
- tDefenderRight->setIdlePosition(rightDefPos);
- tDefenderRight->setUseNav(rightNav);
+void PlayKickoffOpp::Positioning(int RobotID){
+ Vector2D CenterOfField;
+ CenterOfField.x=0;
+ CenterOfField.y=0;
+ Segment2D defenderRightLine(Field::ourGoalPost_R,CenterOfField);
+ Segment2D defenderLeftLine(Field::ourGoalPost_L,CenterOfField);
+ Segment2D midAttackerLine(Field::ourGoalCenter,CenterOfField);
+ Position firstIntersection,secondInterSection;
+ Circle2D circleOfCenter(CenterOfField,Field::centerCircle_R);
+ Circle2D circleOfDefense(Field::ourGoalCenter,abs(Field::ourDefPost_L.y-Field::ourDefPost_R.y));
+ if(wm->ourRobot[RobotID].Role==AgentRole::DefenderLeft){
+ Line2D positionLine(CenterOfField,Field::ourGoalPost_L);
+ circleOfDefense.intersection(positionLine,&firstIntersection.loc,&secondInterSection.loc);
+ if(firstIntersection.loc.x>secondInterSection.loc.x){
+ tDefenderLeft->setUseNav(false);
+ firstIntersection.dir=defenderLeftLine.direction().radian();
+ tDefenderLeft->setIdlePosition(firstIntersection);
+ }
+ else{
+ secondInterSection.dir=defenderLeftLine.direction().radian();
+ tDefenderLeft->setUseNav(false);
+ tDefenderLeft->setIdlePosition(secondInterSection);
+ }
- if( leftID != -1)
- {
- if( (wm->ourRobot[leftID].pos.loc - leftDefPos.loc).length() > 250 )
- leftChecker++;
- else
- leftChecker = 0;
}
+ else if(wm->ourRobot[RobotID].Role==AgentRole::DefenderRight){
+ Line2D positionLine(CenterOfField,Field::ourGoalPost_R);
+ circleOfDefense.intersection(positionLine,&firstIntersection.loc,&secondInterSection.loc);
+ if(firstIntersection.loc.x>secondInterSection.loc.x){
+ firstIntersection.dir=defenderRightLine.direction().radian();
+ tDefenderRight->setUseNav(false);
+ tDefenderRight->setIdlePosition(firstIntersection);
+ }
+ else{
+ secondInterSection.dir=defenderRightLine.direction().radian();
+ tDefenderRight->setUseNav(false);
+ tDefenderRight->setIdlePosition(secondInterSection);
+ }
- if( rightID != -1)
- {
- if( (wm->ourRobot[rightID].pos.loc - rightDefPos.loc).length() > 250 )
- rightChecker++;
- else
- rightChecker = 0;
}
+ else if(wm->ourRobot[RobotID].Role==AgentRole::AttackerLeft){
+ Position ourKickerPos=KickerPositioning(wm->oppRobot[kickerId].pos.loc);
+ tAttackerLeft->setUseNav(true);
+ tAttackerLeft->setIdlePosition(ourKickerPos);
- QList opps = wm->kn->ActiveOppAgents();
- opps.removeOne(wm->ref_goalie_opp);
- QList nearest2Ball = wm->kn->findNearestOppositeTo(wm->ball.pos.loc);
- if( nearest2Ball.size() != 0)
- opps.removeOne(nearest2Ball.at(0));
-
- QList nearest;
- int i = 0;
- Line2D toCenter(Vector2D(0,0),ALLOW_NEAR_BALL_RANGE);
- Circle2D cir;
- Vector2D first,second,main;
- Position leftPos,rightPos;
- int numberOfIntersection;
-
- toCenter.assign(wm->ball.pos.loc , Field::ourGoalCenter);
- cir.assign(wm->ball.pos.loc,ALLOW_NEAR_BALL_RANGE);
- numberOfIntersection = cir.intersection(toCenter,&first,&second);
- if( numberOfIntersection == 2)
- {
- if( wm->kn->IsInsideOurField(first))
- main = first;
- else
- main = second;
}
- else if(numberOfIntersection == 1)
- main = first;
-
- tAttackerMid->setIdlePosition(main);
-
- Circle2D secondCircle(main,(2.5)*ROBOT_RADIUS);
- cir.intersection(secondCircle,&leftPos.loc,&rightPos.loc);
-
- if( tAttackerLeft->getID() != -1)
- {
- nearest.clear();
- i = 0;
- nearest = wm->kn->findNearestOppositeTo(opps,Vector2D(0,Field::MinY/2));
- while( ikn->IsInsideSecureArea(wm->oppRobot[nearest.at(i)].pos.loc,wm->ball.pos.loc)
- /*|| (wm->oppRobot[nearest.at(i)].pos.loc-Vector2D(0,Field::MinY/2)).length()>1000*/)
- nearest.removeAt(i);
- else
- i++;
- }
- while( !nearest.isEmpty() )
- {
- int indexOfOpp = nearest.takeFirst();
- Line2D tmp(wm->oppRobot[indexOfOpp].pos.loc,Field::ourGoalCenter);
- Line2D fixedLine(Vector2D(-2*ROBOT_RADIUS,Field::MinY), Vector2D(-2*ROBOT_RADIUS,Field::MaxY));
- Vector2D interSection = tmp.intersection(fixedLine);
- if( !wm->kn->IsInsideSecureArea(interSection,wm->ball.pos.loc) )
- {
- Position pos;
- pos.loc = interSection;
- pos.dir = (wm->oppRobot[indexOfOpp].pos.loc-Field::ourGoalCenter).dir().degree()*AngleDeg::DEG2RAD;
- if( wm->ourRobot[tAttackerLeft->getID()].Role == AgentRole::AttackerLeft)
- {
- if( !wm->kn->isOccupied(tAttackerLeft->getID(), pos.loc) )
- {
- rightPos = pos;
- opps.removeOne(indexOfOpp);
- break;
- }
- }
- }
- }
- tAttackerLeft->setIdlePosition(rightPos);
+ else if(wm->ourRobot[RobotID].Role==AgentRole::AttackerRight || wm->ourRobot[RobotID].Role==AgentRole::AttackerMid){
+ QList oppPlayer=wm->kn->ActiveOppAgents();
+ Position man2manSimulate1,man2manSimulate2;
+ int first=maximumGoalChanceID(oppPlayer);
+ man2manSimulate1.loc.y=wm->oppRobot[first].pos.loc.y;
+ man2manSimulate1.loc.x=-1*wm->oppRobot[first].pos.loc.x;
+ AngleDeg degree1;
+ degree1=wm->oppRobot[first].pos.loc.dir().radian()+(AngleDeg::PI)*2-1;
+ man2manSimulate1.dir=degree1.degree();
+ oppPlayer.removeOne(first);
+ int second=maximumGoalChanceID(oppPlayer);
+ man2manSimulate2.loc.y=wm->oppRobot[second].pos.loc.y;
+ man2manSimulate2.loc.x=-1*wm->oppRobot[second].pos.loc.x;
+ AngleDeg degree2;
+ degree2=wm->oppRobot[second].pos.loc.dir().radian()+(AngleDeg::PI)*2+1;
+ man2manSimulate2.dir=degree2.degree();
+ qDebug()<<"First"<ourRobot[tAttackerMid->getID()].pos.loc.y>wm->ourRobot[tAttackerRight->getID()].pos.loc.y){
+ tAttackerMid->setIdlePosition(man2manSimulate1);
+ tAttackerRight->setIdlePosition(man2manSimulate2);
+ /*}else{
+ tAttackerRight->setIdlePosition(man2manSimulate1);
+ tAttackerMid->setIdlePosition(man2manSimulate2);
+ }*/
+ // maximumGoalChanceID(oppPlayer);
+ }
+ else if(wm->ourRobot[RobotID].Role==AgentRole::Golie){
+ Vector2D goalie;
+ goalie.x=Field::ourGoalCenter.x+90;
+ goalie.y=Field::ourGoalCenter.y;
+ tGolie->setIdlePosition(goalie);
}
+}
- if( tAttackerRight->getID() != -1)
- {
- nearest.clear();
- nearest = wm->kn->findNearestOppositeTo(opps,Vector2D(0,Field::MaxY/2));
- i = 0;
- while( ikn->IsInsideSecureArea(wm->oppRobot[nearest.at(i)].pos.loc,wm->ball.pos.loc)
- /*|| (wm->oppRobot[nearest.at(i)].pos.loc -Vector2D(0,Field::MaxY/2)).length()>1000*/)
- nearest.removeAt(i);
- else
- i++;
- }
- while( !nearest.isEmpty() )
- {
- int indexOfOpp = nearest.takeFirst();
- Line2D tmp(wm->oppRobot[indexOfOpp].pos.loc,Field::ourGoalCenter);
- Line2D fixedLine(Vector2D(-2*ROBOT_RADIUS,Field::MinY), Vector2D(-2*ROBOT_RADIUS,Field::MaxY));
- Vector2D interSection = tmp.intersection(fixedLine);
- if( !wm->kn->IsInsideSecureArea(interSection,wm->ball.pos.loc) )
- {
- Position pos;
- pos.loc = interSection;
- pos.dir = (wm->oppRobot[indexOfOpp].pos.loc-Field::ourGoalCenter).dir().degree()*AngleDeg::DEG2RAD;
- if( wm->ourRobot[tAttackerRight->getID()].Role == AgentRole::AttackerRight)
- {
- if( !wm->kn->isOccupied(tAttackerRight->getID(), pos.loc) )
- {
- leftPos = pos;
- opps.removeOne(indexOfOpp);
- break;
- }
+void PlayKickoffOpp::execute(){
+ findOppKickerId();
+ Vector2D CenterOfField;
+ Position center;
+ center.loc=CenterOfField;
+ CenterOfField.x=0;
+ CenterOfField.y=0;
+ QList ourCurrentPlayer=wm->kn->ActiveAgents();
+ for(int i=0;iourRobot[i].Status=AgentStatus::Idle;
+ }
+ initRole();
+ for(int i=0;icmgs.canKickBall()){
+ int counter=0;
+ tAttackerLeft->setUseNav(true);
+ tAttackerMid->setUseNav(true);
+ tAttackerRight->setUseNav(true);
+ QList oppPlayer=wm->kn->ActiveOppAgents();
+ for(int i=0;ioppRobot[oppPlayer.at(i)].pos.dir;
+ if(wm->kn->IsInsideCircle(wm->oppRobot[oppPlayer.at(i)].pos.loc,CenterOfField,Field::centerCircle_R+3000)
+ &&!wm->kn->IsReadyForKick(wm->oppRobot[oppPlayer.at(i)].pos,center,wm->ball.pos.loc)){
+ counter++;
+ Vector2D defense;
+ if(counter==1){
+ defense.x=wm->oppRobot[oppPlayer.at(i)].pos.loc.x-ROBOT_RADIUS-100;
+ defense.y=wm->oppRobot[oppPlayer.at(i)].pos.loc.y;
+ tAttackerLeft->setIdlePosition(defense);
+ }else if(counter==2){
+ defense.x=wm->oppRobot[oppPlayer.at(i)].pos.loc.x-ROBOT_RADIUS-100;
+ defense.y=wm->oppRobot[oppPlayer.at(i)].pos.loc.y;
+ tAttackerRight->setIdlePosition(defense);
}
}
}
- tAttackerRight->setIdlePosition(leftPos);
- }
+ counter==0;
+
+ }
}
-void PlayKickoffOpp::execute()
-{
- QList activeAgents=wm->kn->ActiveAgents();
- initRole();
- for(int i=0;i oppPlayer);
+ bool isInsideTriangle(Vector2D pos,Vector2D vertex1);
+ Position KickerPositioning(Vector2D oppKicker);
+ void findOppKickerId();
};
#endif // PLAYKICKOFFOPP_H
diff --git a/src/ai/play/playkickoffour.cpp b/src/ai/play/playkickoffour.cpp
old mode 100644
new mode 100755
index 521a9a3..cb1844b
--- a/src/ai/play/playkickoffour.cpp
+++ b/src/ai/play/playkickoffour.cpp
@@ -140,7 +140,7 @@ void PlayKickoffOur::execute()
setPositions();
- if( wm->cmgs.canKickBall() )
+ if( wm->cmgs.gameOn())
wm->ourRobot[tAttackerMid->getID()].Status = AgentStatus::Kicking;
}
diff --git a/src/ai/play/playkickoffour.h b/src/ai/play/playkickoffour.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/playlearning.cpp b/src/ai/play/playlearning.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/playlearning.h b/src/ai/play/playlearning.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/playpenaltyopp.cpp b/src/ai/play/playpenaltyopp.cpp
old mode 100644
new mode 100755
index 50b877f..1ffefda
--- a/src/ai/play/playpenaltyopp.cpp
+++ b/src/ai/play/playpenaltyopp.cpp
@@ -6,6 +6,7 @@ PlayPenaltyOpp::PlayPenaltyOpp(WorldModel *worldmodel, QObject *parent) :
tGoalie=new TacticGoalie(wm);
tDefenderRight=new TacticDefender(wm);
tDefenderLeft=new TacticDefender(wm);
+ tDefenderMid=new TacticDefender(wm);
tAttackerMid = new TacticAttacker(wm);
tAttackerRight = new TacticAttacker(wm);
tAttackerLeft = new TacticAttacker(wm);
@@ -14,9 +15,9 @@ PlayPenaltyOpp::PlayPenaltyOpp(WorldModel *worldmodel, QObject *parent) :
int PlayPenaltyOpp::enterCondition()
{
if(wm->cmgs.theirPenaltyKick())
- return 100;
+ return 100;//100
else
- return 0;
+ return 0;//0
}
void PlayPenaltyOpp::setTactics(int index)
@@ -40,6 +41,8 @@ void PlayPenaltyOpp::setTactics(int index)
case AgentRole::AttackerRight:
tactics[index] = tAttackerRight;
break;
+ case AgentRole::DefenderMid:
+ tactics[index] = tDefenderMid;
default:
break;
}
@@ -47,62 +50,149 @@ void PlayPenaltyOpp::setTactics(int index)
void PlayPenaltyOpp::setPositions()
{
- Position goaliePos,leftDefPos,rightDefPos;
- bool leftNav, rightNav;
- zonePositions(tDefenderLeft->getID(),tDefenderRight->getID(),-1,goaliePos,leftDefPos,leftNav,rightDefPos,rightNav);
+ Position goaliePos,leftDefPos,rightDefPos,MidDefPos,rightAttackerPos,leftAttackerPos,midAttackerPos;
+ if(wm->ball.vel.loc.length()<0.2){
+ int kickerId;
+ if(wm->kn->findNearestOppositeTo(wm->ball.pos.loc).length()!=0){
+ kickerId=wm->kn->findNearestOppositeTo(wm->ball.pos.loc).at(0);
+ Line2D shot(wm->ball.pos.loc,wm->oppRobot[kickerId].pos.loc);
+ Vector2D GL,GR;
+ GL=Field::ourGoalPost_L;
+ GR=Field::ourGoalPost_R;
+ if(Field::ourGoalPost_L.y>0){
+ GL.y+=200;
+ }
+ else{
+ GL.y-=200;
+ }
+ if(Field::ourGoalPost_R.y>0){
+ GR.y+=200;
+ }
+ else{
+ GR.y-=200;
+ }
+ Segment2D gLine(GL,GR);
+ goaliePos.loc=gLine.intersection(shot);
+ if(gLine.contains(goaliePos.loc)==false){
+ goaliePos.loc=Field::ourGoalCenter;
+ }
+ goaliePos.dir=(wm->ball.pos.loc-goaliePos.loc).dir().radian();
+ }
+ else{
+ goaliePos.loc=Field::ourGoalCenter;
+ }
+ //
+ }
+ else{
+ Vector2D f;
+ Vector2D a;
+ f.x=wm->ball.pos.loc.x+wm->ball.vel.loc.x;
+ f.y=wm->ball.pos.loc.y+wm->ball.vel.loc.y;
+ Line2D shot(wm->ball.pos.loc,f);
+ Segment2D gLine(Field::ourGoalPost_L,Field::ourGoalPost_R);
+ a=gLine.intersection(shot);
+ if(gLine.contains(a)){
+ goaliePos.loc=a;
+ }
+ else{
+ goaliePos.loc=Field::ourGoalCenter;
+ }
+ goaliePos.dir=(wm->ball.pos.loc-goaliePos.loc).dir().radian();
+ }
+ if(wm->ball.pos.loc.dist(Field::ourGoalCenter)>450){
+ if(wm->ourRobot[tGoalie->getID()].pos.loc.dist(goaliePos.loc)>100){
+ if(goaliePos.loc.y>Field::ourGoalCenter.y){
+ goaliePos.loc.y+=20;
+ }
+ if(goaliePos.loc.ysetIdlePosition(goaliePos);
+ wm->debug_pos.append(goaliePos.loc);
+ //wm->debug_pos.append(goaliePos.loc); arminTest
+
+ MidDefPos.loc.x=(4*Field::ourGoalCenter.x+Field::oppGoalCenter.x)/5;
+ MidDefPos.loc.y=(4*Field::ourGoalCenter.y+Field::oppGoalCenter.y)/5;
+ tDefenderMid->setIdlePosition(MidDefPos);
+
+ leftDefPos.loc.x=(4*Field::ourGoalCenter.x+Field::oppGoalCenter.x)/5;
+ leftDefPos.loc.y=+500;
tDefenderLeft->setIdlePosition(leftDefPos);
+
+ rightDefPos.loc.x=(4*Field::ourGoalCenter.x+Field::oppGoalCenter.x)/5;
+ rightDefPos.loc.y=-500;
tDefenderRight->setIdlePosition(rightDefPos);
- tGoalie->setIdlePosition(goaliePos);
- tAttackerMid->setIdlePosition(Field::oppPenaltyParallelLineCenter);
- tAttackerRight->setIdlePosition(Vector2D(Field::oppPenaltyParallelLineCenter.x,
- Field::oppPenaltyParallelLineCenter.y - (Field::MaxY*0.75)));
- tAttackerLeft->setIdlePosition(Vector2D(Field::oppPenaltyParallelLineCenter.x,
- Field::oppPenaltyParallelLineCenter.y + (Field::MaxY*0.75)));
+ rightAttackerPos.loc.x=(2*Field::ourGoalCenter.x+Field::oppGoalCenter.x)/3;
+ rightAttackerPos.loc.y=-1500;
+ tAttackerRight->setIdlePosition(rightAttackerPos);
+
+ leftAttackerPos.loc.x=(2*Field::ourGoalCenter.x+Field::oppGoalCenter.x)/3;
+ leftAttackerPos.loc.y=+1500;
+ tAttackerLeft->setIdlePosition(leftAttackerPos);
+
+ midAttackerPos.loc.x=(2*Field::ourGoalCenter.x+Field::oppGoalCenter.x)/3;
+ midAttackerPos.loc.y=0;
+ tAttackerMid->setIdlePosition(midAttackerPos);
+
+
+ //wm->debug_pos.append(goaliePos.loc);
}
void PlayPenaltyOpp::initRole()
{
- QList activeAgents=wm->kn->ActiveAgents();
-
-
- activeAgents.removeOne(wm->ref_goalie_our);
+ QList activeAgents=wm->kn->ActiveAgents();
- wm->ourRobot[wm->ref_goalie_our].Role = AgentRole::Golie;
+ if(wm->ourRobot[wm->ref_goalie_our].isValid){
+ activeAgents.removeOne(wm->ref_goalie_our);
+ wm->ourRobot[wm->ref_goalie_our].Role = AgentRole::Golie;
+ }
switch (activeAgents.length()) {
case 1:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
+ //wm->ourRobot[wm->kn->ActiveAgents().at(0)].Role=Golie;
+ wm->ourRobot[activeAgents.at(0)].Role=DefenderMid;
break;
case 2:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
+ //wm->ourRobot[wm->kn->ActiveAgents().at(0)].Role=Golie;
+ wm->ourRobot[activeAgents.at(0)].Role=DefenderRight;
+ wm->ourRobot[activeAgents.at(1)].Role=DefenderLeft;
break;
case 3:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerMid;
+ //wm->ourRobot[wm->kn->ActiveAgents().at(0)].Role=Golie;
+ wm->ourRobot[activeAgents.at(0)].Role=DefenderMid;
+ wm->ourRobot[activeAgents.at(1)].Role=DefenderRight;
+ wm->ourRobot[activeAgents.at(2)].Role=DefenderLeft;
break;
case 4:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerRight;
+ //wm->ourRobot[wm->kn->ActiveAgents().at(0)].Role=Golie;
+ wm->ourRobot[activeAgents.at(0)].Role=DefenderMid;
+ wm->ourRobot[activeAgents.at(1)].Role=DefenderRight;
+ wm->ourRobot[activeAgents.at(2)].Role=DefenderLeft;
+ wm->ourRobot[activeAgents.at(3)].Role=AttackerMid;
break;
case 5:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerMid;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerRight;
+ //wm->ourRobot[wm->kn->ActiveAgents().at(0)].Role=Golie;
+ wm->ourRobot[activeAgents.at(0)].Role=DefenderMid;
+ wm->ourRobot[activeAgents.at(1)].Role=DefenderRight;
+ wm->ourRobot[activeAgents.at(2)].Role=DefenderLeft;
+ wm->ourRobot[activeAgents.at(3)].Role=AttackerRight;
+ wm->ourRobot[activeAgents.at(4)].Role=AttackerLeft;
+ break;
+ default:
break;
}
+
+
}
void PlayPenaltyOpp::execute()
{
+
QList activeAgents=wm->kn->ActiveAgents();
initRole();
@@ -117,6 +207,8 @@ void PlayPenaltyOpp::execute()
int index = activeAgents.takeFirst();
setTactics(index);
}
-
+ wm->debug_pos.clear();
setPositions();
+
+ //qDebug()<<"FUCK";
}
diff --git a/src/ai/play/playpenaltyopp.h b/src/ai/play/playpenaltyopp.h
old mode 100644
new mode 100755
index b749f93..38c1bd7
--- a/src/ai/play/playpenaltyopp.h
+++ b/src/ai/play/playpenaltyopp.h
@@ -19,6 +19,7 @@ class PlayPenaltyOpp : public Play
private:
TacticDefender* tDefenderLeft;
TacticDefender* tDefenderRight;
+ TacticDefender* tDefenderMid;
TacticGoalie* tGoalie;
TacticAttacker* tAttackerMid;
TacticAttacker* tAttackerRight;
diff --git a/src/ai/play/playpenaltyour.cpp b/src/ai/play/playpenaltyour.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/playpenaltyour.h b/src/ai/play/playpenaltyour.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/playpreparing.cpp b/src/ai/play/playpreparing.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/play/playpreparing.h b/src/ai/play/playpreparing.h
old mode 100644
new mode 100755
diff --git a/src/ai/play/playstop.cpp b/src/ai/play/playstop.cpp
old mode 100644
new mode 100755
index af9b77c..30373d6
--- a/src/ai/play/playstop.cpp
+++ b/src/ai/play/playstop.cpp
@@ -3,14 +3,14 @@
PlayStop::PlayStop(WorldModel *worldmodel, QObject *parent) :
Play("PlayStop", worldmodel, parent)
{
- tGolie=new TacticGoalie(wm);
-
- tDefenderLeft=new TacticDefender(wm);
- tDefenderRight=new TacticDefender(wm);
-
- tStopMid=new TacticStop(wm);
- tStopLeft=new TacticStop(wm);
- tStopRight=new TacticStop(wm);
+ tGoalie = new TacticGoalie(wm);
+ tDefenderLeft = new TacticDefender(wm);
+ tDefenderRight = new TacticDefender(wm);
+ tStopMid = new TacticStop(wm);
+ tStopLeft = new TacticStop(wm);
+ tStopRight = new TacticStop(wm);
+ tAttackerLeft = new TacticAttacker(wm);
+ tAttackerRight = new TacticAttacker(wm);
leftChecker = 0;
rightChecker = 0;
@@ -18,72 +18,47 @@ PlayStop::PlayStop(WorldModel *worldmodel, QObject *parent) :
int PlayStop::enterCondition()
{
- if(wm->gs == STATE_Stop)
+ /*if(wm->gs == STATE_Stop)
return 100;
else if(wm->cmgs.canMove() && wm->cmgs.gameOn()==false && wm->cmgs.allowedNearBall()==false)
return 10;
else
- return 0;
- // return 20000;
-}
-
-bool PlayStop::collisionwithDefenders(Vector2D center, Vector2D left, Vector2D right)
-{
- if( ((center-wm->ourRobot[tDefenderLeft->getID()].pos.loc).length() < 2*ROBOT_RADIUS)
- ||
- ((left-wm->ourRobot[tDefenderLeft->getID()].pos.loc).length() < 2*ROBOT_RADIUS)
- ||
- ((right-wm->ourRobot[tDefenderLeft->getID()].pos.loc).length() < 2*ROBOT_RADIUS)
- ||
- ((center-wm->ourRobot[tDefenderRight->getID()].pos.loc).length() < 2*ROBOT_RADIUS)
- ||
- ((left-wm->ourRobot[tDefenderRight->getID()].pos.loc).length() < 2*ROBOT_RADIUS)
- ||
- ((right-wm->ourRobot[tDefenderRight->getID()].pos.loc).length() < 2*ROBOT_RADIUS)
- )
- return true;
-
- return false;
-}
-
-bool PlayStop::oneOfDefendersIsInPenalty(Vector2D leftPos, Vector2D midPos, Vector2D rightPos)
-{
- if( wm->kn->IsInsideGolieArea(leftPos) || wm->kn->IsInsideGolieArea(midPos) || wm->kn->IsInsideGolieArea(rightPos))
- return true;
-
- return false;
+ return 0;*/
+ return 0;
}
void PlayStop::initRole()
{
- QList activeAgents=wm->kn->ActiveAgents();
- activeAgents.removeOne(wm->ref_goalie_our);
+ QList actives = wm->kn->ActiveAgents();
+ actives.removeOne(wm->ref_goalie_our);
wm->ourRobot[wm->ref_goalie_our].Role = AgentRole::Golie;
- switch (activeAgents.length()) {
+ switch (actives.length()) {
case 1:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::DefenderLeft;
break;
case 2:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::DefenderLeft;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::DefenderRight;
break;
case 3:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerMid;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::DefenderLeft;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::DefenderRight;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::AttackerMid;
break;
case 4:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerRight;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::DefenderLeft;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::DefenderRight;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::AttackerMid;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::AttackerLeft;
break;
case 5:
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderRight;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::DefenderLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerMid;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerLeft;
- wm->ourRobot[activeAgents.takeFirst()].Role = AgentRole::AttackerRight;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::DefenderLeft;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::DefenderRight;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::AttackerMid;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::AttackerLeft;
+ wm->ourRobot[actives.takeFirst()].Role = AgentRole::AttackerRight;
+ break;
+ default:
break;
}
}
@@ -94,7 +69,7 @@ void PlayStop::setTactics(int index)
switch (wm->ourRobot[index].Role) {
case AgentRole::Golie:
- tactics[index] = tGolie;
+ tactics[index] = tGoalie;
break;
case AgentRole::DefenderLeft:
tactics[index] = tDefenderLeft;
@@ -181,117 +156,113 @@ void PlayStop::setPositions()
rightChecker = 0;
}
- tGolie->setIdlePosition(goaliePos);
+ tGoalie->setIdlePosition(goaliePos);
- if(wm->kn->IsInsideGolieArea(wm->ball.pos.loc) )
- {
- tStopLeft->setStopPosition(Vector2D(Field::MinX/2.0,Field::ourGoalPost_L.y+200));
- tStopRight->setStopPosition(Vector2D(Field::MinX/2.0,Field::ourGoalPost_R.y-200));
- tStopMid->setStopPosition(Vector2D(Field::MinX/2.0,Field::ourGoalCenter.y));
- }
- else if( wm->kn->IsInsideNearArea(wm->ball.pos.loc) )
+ if (wm->kn->IsInsideGolieArea(wm->ball.pos.loc))
{
- Vector2D candidateL_1, candidateL_2, mainL;
-
- Circle2D cir_l(Field::defenceLineLinear_L,Field::goalCircle_R+ROBOT_RADIUS);
- Line2D thirty_l(Field::defenceLineLinear_L,AngleDeg(30));
- cir_l.intersection(thirty_l,&candidateL_1,&candidateL_2);
- if( wm->kn->IsInsideField(candidateL_1) && !wm->kn->IsInsideGolieArea(candidateL_1) )
- mainL = candidateL_1;
- else
- mainL = candidateL_2;
-
- tStopLeft->setStopPosition(Vector2D(mainL.x,sign(wm->ball.pos.loc.y)*mainL.y));
- tStopMid->setStopPosition(Vector2D(Field::MinX+300,-sign(wm->ball.pos.loc.y)*1400));
- tStopRight->setStopPosition(Vector2D(mainL.x,-sign(wm->ball.pos.loc.y)*mainL.y));
+ tStopMid->setStopPosition({Field::ourGoalCenter.x + 2250, 0});
+ tStopLeft->setStopPosition({Field::ourGoalCenter.x + 2250, 1250});
+ tStopRight->setStopPosition({Field::ourGoalCenter.x + 2250, -1250});
}
- else
+ else if (wm->ball.pos.loc.x < Field::ourGoalCenter.x + (Field::MaxX * 2) / 3)
{
- Vector2D finalPos,notImportant,leftPos,rightPos;
-
- Circle2D robotCircle(wm->ball.pos.loc,ALLOW_NEAR_BALL_RANGE);
- Segment2D line2Goal(wm->ball.pos.loc,Field::ourGoalCenter);
- robotCircle.intersection(line2Goal,&finalPos,¬Important);
-
- Circle2D secondCircle(finalPos,(2.5)*ROBOT_RADIUS);
- robotCircle.intersection(secondCircle,&leftPos,&rightPos);
-
- if( !wm->kn->IsInsideField(leftPos) )
+ Segment2D seg(Field::ourGoalCenter, wm->ball.pos.loc);
+ Circle2D ballcir(wm->ball.pos.loc, ALLOW_NEAR_BALL_RANGE);
+ Vector2D fdot, sdot;
+ ballcir.intersection(seg, &fdot, &sdot);
+
+ Circle2D goalieCir (Field::ourGoalCenter, 1300);
+ Line2D linetest (Field::ourGoalCenter, wm->ball.pos.loc);
+ if (wm->kn->IsInsideGolieArea(fdot))
{
- leftPos = finalPos;
- finalPos = rightPos;
-
- Vector2D leftPos2,rightPos2;
- Circle2D secondCircle(finalPos,(2.5)*ROBOT_RADIUS);
- robotCircle.intersection(secondCircle,&leftPos2,&rightPos2);
-
- if( leftPos.dist(leftPos2) < leftPos.dist(rightPos2) )
- rightPos = rightPos2;
- else
- rightPos = leftPos2;
-
+ goalieCir.intersection(linetest, &fdot, &sdot);
+ if (fdot.x < sdot.x)
+ fdot = sdot;
}
- else if( !wm->kn->IsInsideField(rightPos) )
- {
- rightPos = finalPos;
- finalPos = leftPos;
- Vector2D leftPos2,rightPos2;
- Circle2D secondCircle(finalPos,(2.5)*ROBOT_RADIUS);
- robotCircle.intersection(secondCircle,&leftPos2,&rightPos2);
+ tStopMid->setStopPosition(fdot);
- if( rightPos.dist(leftPos2) < rightPos.dist(rightPos2) )
- leftPos = rightPos2;
- else
- leftPos = leftPos2;
- }
+ tactics[tStopLeft->getID()] = tAttackerLeft;
+ tactics[tStopRight->getID()] = tAttackerRight;
- if( collisionwithDefenders(finalPos,leftPos,rightPos) || oneOfDefendersIsInPenalty(leftPos,finalPos,rightPos) )
+ Marking def;
+ def.setWorldModel(wm); //??
+ bool isMatched;
+ QList opp = wm->kn->ActiveOppAgents();
+ QList our;
+ our.append(tAttackerLeft->getID());
+ our.append(tAttackerRight->getID());
+ QList m2m = def.findMarking(our , opp, isMatched);
+ if (isMatched)
{
- if( wm->kn->IsInsideRect(wm->ball.pos.loc,Vector2D(Field::MinX,Field::MaxY),Vector2D(0,0.25*Field::MaxY))
- ||
- wm->kn->IsInsideRect(wm->ball.pos.loc,Vector2D(Field::MinX,0.25*Field::MinY),Vector2D(0,Field::MinY)) )
+ for (int i = 0; i < m2m.size(); i++)
{
- Vector2D candidateL_1, candidateL_2, mainL;
-
- Circle2D cir_l(Field::defenceLineLinear_L,Field::goalCircle_R+ROBOT_RADIUS);
- Line2D thirty_l(Field::defenceLineLinear_L,AngleDeg(30));
- cir_l.intersection(thirty_l,&candidateL_1,&candidateL_2);
- if( wm->kn->IsInsideField(candidateL_1) && !wm->kn->IsInsideGolieArea(candidateL_1) )
- mainL = candidateL_1;
- else
- mainL = candidateL_2;
-
- tStopLeft->setStopPosition(Vector2D(mainL.x,sign(wm->ball.pos.loc.y)*mainL.y));
- tStopMid->setStopPosition(Vector2D(Field::ourPenaltySpot.x+200,Field::ourPenaltySpot.y));
- tStopRight->setStopPosition(Vector2D(mainL.x,-sign(wm->ball.pos.loc.y)*mainL.y));
- }
- else
- {
- //tStopLeft->setStopPosition(Vector2D(wm->ourRobot[tDefenderLeft->getID()].pos.loc.x
- // , wm->ourRobot[tDefenderLeft->getID()].pos.loc.y+5*ROBOT_RADIUS));
- finalPos = Vector2D(wm->ourRobot[tDefenderLeft->getID()].pos.loc.x,
- 0.5*(wm->ourRobot[tDefenderLeft->getID()].pos.loc.y+wm->ourRobot[tDefenderRight->getID()].pos.loc.y)
- );
- tStopLeft->setStopPosition(Vector2D(finalPos.x,finalPos.y+4.5*ROBOT_RADIUS));
- tStopMid->setStopPosition(Vector2D(finalPos.x,finalPos.y-6.5*ROBOT_RADIUS));
- tStopRight->setStopPosition(Vector2D(finalPos.x,finalPos.y-4.5*ROBOT_RADIUS));
+ wm->ourRobot[m2m.at(i).ourI].Status = AgentStatus::BlockingRobot;
+
+ switch (wm->ourRobot[m2m.at(i).ourI].Role) {
+ case AgentRole::DefenderLeft:
+ tDefenderLeft->setPlayerToKeep(m2m.at(i).oppI);
+ break;
+ case AgentRole::DefenderRight:
+ tDefenderRight->setPlayerToKeep(m2m.at(i).oppI);
+ break;
+ case AgentRole::AttackerLeft:
+ tAttackerLeft->setPlayerToKeep(m2m.at(i).oppI);
+ break;
+ case AgentRole::AttackerRight:
+ tAttackerRight->setPlayerToKeep(m2m.at(i).oppI);
+ break;
+ default:
+ break;
+ }
}
}
- else
- {
- tStopLeft->setStopPosition(leftPos);
- tStopMid->setStopPosition(finalPos);
- tStopRight->setStopPosition(rightPos);
- }
+ }
+ else if (wm->ball.pos.loc.x < Field::ourGoalCenter.x + (Field::MaxX * 2)* 2 / 3)
+ {
+ Vector2D fPosAttMid, fPosAttLeft, fPosAttRight, sec;
+ double slope, degree, deltaa;
+ slope = (wm->ball.pos.loc.y - Field::ourGoalCenter.y) / (wm->ball.pos.loc.x - Field::ourGoalCenter.x);
+ degree = atan(slope);
+ deltaa = 2 * asin( ROBOT_RADIUS / ALLOW_NEAR_BALL_RANGE );
+ AngleDeg deg(degree * 57.32), delta(deltaa * 57.32);
+ AngleDeg leftAttDeg, rightAttDeg;
+ leftAttDeg = operator -(deg, delta);
+ rightAttDeg = operator +(deg, delta);
+ Line2D leftAttLine(wm->ball.pos.loc, leftAttDeg.degree() - 1.5);
+ Line2D rightAttLine(wm->ball.pos.loc, rightAttDeg.degree() + 1.5);
+ Circle2D cir(wm->ball.pos.loc, ALLOW_NEAR_BALL_RANGE);
+ cir.intersection(leftAttLine, &fPosAttLeft, &sec);
+ if (sec.x < fPosAttLeft.x)
+ fPosAttLeft = sec;
+ cir.intersection(rightAttLine, &fPosAttRight, &sec);
+ if (sec.x < fPosAttRight.x)
+ fPosAttRight = sec;
+
+ tStopLeft->setStopPosition(fPosAttLeft);
+ tStopRight->setStopPosition(fPosAttRight);
+
+ Segment2D seg(Field::ourGoalCenter, wm->ball.pos.loc);
+ Circle2D ballcir(wm->ball.pos.loc, ALLOW_NEAR_BALL_RANGE);
+ Vector2D fdot, sdot;
+ ballcir.intersection(seg, &fdot, &sdot);
+ tStopMid->setStopPosition(fdot);
+ }
+ else if (Field::ourGoalCenter.x + (Field::MaxX * 2)* 2 / 3 < wm->ball.pos.loc.x)
+ {
+ Segment2D seg(Field::ourGoalCenter, wm->ball.pos.loc);
+ Circle2D ballcir(wm->ball.pos.loc, ALLOW_NEAR_BALL_RANGE);
+ Vector2D fdot, sdot;
+ ballcir.intersection(seg, &fdot, &sdot);
+ tStopMid->setStopPosition(fdot);
+
+ tStopLeft->setStopPosition({wm->ball.pos.loc.x - 2250, 1250});
+ tStopRight->setStopPosition({wm->ball.pos.loc.x - 2250, -1250});
}
}
void PlayStop::execute()
{
- wm->passPoints.clear();
- wm->debug_pos.clear();
-
QList activeAgents=wm->kn->ActiveAgents();
for(int i=0;i
+
+class PlayStop_Hejazi : public Play
+{
+public:
+ explicit PlayStop_Hejazi(WorldModel *worldmodel, QObject *parent = 0);
+ virtual void execute();
+ virtual void initRole();
+ PlayStop_Hejazi();
+};
+
+#endif // PLAYSTOP_HEJAZI_H
diff --git a/src/ai/play/playtest.cpp b/src/ai/play/playtest.cpp
old mode 100644
new mode 100755
index 51df22f..e494431
--- a/src/ai/play/playtest.cpp
+++ b/src/ai/play/playtest.cpp
@@ -1,14 +1,14 @@
#include "playtest.h"
PlayTest::PlayTest(WorldModel *worldmodel, QObject *parent) :
Play("PlayTest", worldmodel, parent)
-{//////////////////////////////////
- test = new TacticTest(wm);
- test2 = new TacticTest2(wm);
- ///////////////////////////////////
+{
+ tTest = new TacticTest(wm);
+ tTest2 = new TacticTest(wm);
}
int PlayTest::enterCondition()
{
+ //return 20000;
return 0;
}
@@ -17,10 +17,15 @@ void PlayTest::initRole()
}
void PlayTest::execute()
-{//---////////////////////////////////////////////////////
-
- tactics[0] = test;
- tactics[1] = test;
- tactics[2] = test;
-
+{
+// std::cout << wm->kn->ActiveAgents()[0] << std::endl;
+// wm->debug_pos.clear();
+// wm->debug_pos.append(wm->ourRobot[1].pos.loc);
+// wm->debug_pos.append(wm->ourRobot[0].pos.loc);
+ tactics[4] = tTest;
+// for(int i=0;ikn->ActiveAgents().length();i++){
+// tactics[wm->kn->ActiveAgents()[i]] = tTest;
+// }
+ //wm->debug_pos.clear();
+ //wm->debug_pos.append(Vector2D (0,0));
}
diff --git a/src/ai/play/playtest.h b/src/ai/play/playtest.h
old mode 100644
new mode 100755
index 106b915..6ea392a
--- a/src/ai/play/playtest.h
+++ b/src/ai/play/playtest.h
@@ -11,12 +11,8 @@ class PlayTest : public Play
virtual void execute();
virtual void initRole();
virtual int enterCondition();
-
- ////////////////////////////
private:
- int flag=0;
- TacticTest *test;
- TacticTest2 *test2;
- ///////////////////////////
+ TacticTest* tTest;
+ TacticTest* tTest2;
};
#endif // PLAYTEST_H
diff --git a/src/ai/play/playtest2.cpp b/src/ai/play/playtest2.cpp
old mode 100644
new mode 100755
index 0c70527..f79a93f
--- a/src/ai/play/playtest2.cpp
+++ b/src/ai/play/playtest2.cpp
@@ -3,11 +3,7 @@
PlayTest2::PlayTest2(WorldModel *worldmodel, QObject *parent) :
Play("PlayTest2", worldmodel, parent)
{
- // Goaler.
- tGolie = new TacticGoalie(wm);
- tTF = new TacticTestFriction(wm);
- thalt = new TacticHalt(wm);
- tTest = new TacticTest(wm);
+ tTest = new TacticTest2(wm);
}
int PlayTest2::enterCondition()
@@ -15,15 +11,125 @@ int PlayTest2::enterCondition()
return 0;
}
+int PlayTest2::Parabola_intersection(Vector2D site1, Vector2D site2, double l, Vector2D *v1, Vector2D *v2)
+{
+ double a1, b1, c1;
+ double a2, b2, c2;
+ double a, b, c;
+ double delta;
+
+ a1 = 0.5 / (site1.y - l);
+ b1 = site1.x / (l - site1.y);
+ c1 = ( 0.5 * (site1.y + l) ) + ( 0.5 * site1.x * site1.x / (site1.y -l) );
+ //cout << a1 << "||" << b1 << "||" << c1 << endl;
+
+ a2 = 0.5 / (site2.y - l);
+ b2 = site2.x / (l - site2.y);
+ c2 = ( 0.5 * (site2.y + l) ) + ( 0.5 * site2.x * site2.x / (site2.y -l) );
+ //cout << a2 << "||" << b2 << "||" << c2 << endl;
+
+ a = a1 - a2;
+ b = b1 - b2;
+ c = c1 - c2;
+ //cout << a << "||" << b << "||" << c << endl;
+
+ delta = b * b - 4 * a * c;
+
+ if (a == 0)
+ {
+ if (b == 0)
+ return 0;
+ else
+ {
+ v1->x = (-1) * c / b;
+ v1->y = a1 * v1->x * v1->x + b1 * v1->x + c1;
+
+ return 1;
+ }
+ }
+ else
+ {
+ if (delta > 0)
+ {
+ v1->x = ( (-1) * b - sqrt(delta) ) / (2 * a);
+ v1->y = a1 * v1->x * v1->x + b1 * v1->x + c1;
+ v2->x = ( (-1) * b + sqrt(delta) ) / (2 * a);
+ v2->y = a1 * v2->x * v2->x + b1 * v2->x + c1;
+
+ return 2;
+ }
+ else if (delta == 0)
+ {
+ v1->x = ((-1) * b) / (2 * a);
+ v1->y = a1 * v1->x * v1->x + b1 * v1->x + c1;
+
+ return 1;
+ }
+ else
+ return 0;
+ }
+}
+
void PlayTest2::initRole()
{
}
+
void PlayTest2::execute()
{
-// tactics[wm->ref_goalie_our] = tGolie;
- tactics[3] = tTest;
- qDebug()<<"Ball Speed is "<ball.vel.loc.length();
+ if(wm->gs == STATE_Stop){
+ tactics[wm->ref_goalie_our] = tTest;
+ //step1
+ if(wm->kn->ActiveAgents().size() == 3){
+ tactics[wm->kn->ActiveAgents()[0]] = tTest;
+ tactics[wm->kn->ActiveAgents()[1]] = tTest;
+ tactics[wm->kn->ActiveAgents()[2]] = tTest;
+ }
+ if(wm->kn->ActiveAgents().size() == 4){
+ tactics[wm->kn->ActiveAgents()[0]] = tTest;
+ tactics[wm->kn->ActiveAgents()[1]] = tTest;
+ tactics[wm->kn->ActiveAgents()[2]] = tTest;
+ tactics[wm->kn->ActiveAgents()[3]] = tTest;
+ }
+ if(wm->kn->ActiveAgents().size() == 5){
+ tactics[wm->kn->ActiveAgents()[0]] = tTest;
+ tactics[wm->kn->ActiveAgents()[1]] = tTest;
+ tactics[wm->kn->ActiveAgents()[2]] = tTest;
+ tactics[wm->kn->ActiveAgents()[3]] = tTest;
+ tactics[wm->kn->ActiveAgents()[4]] = tTest;
+ }
+ if(wm->kn->ActiveAgents().size() == 6){
+ tactics[wm->kn->ActiveAgents()[0]] = tTest;
+ tactics[wm->kn->ActiveAgents()[1]] = tTest;
+ tactics[wm->kn->ActiveAgents()[2]] = tTest;
+ tactics[wm->kn->ActiveAgents()[3]] = tTest;
+ tactics[wm->kn->ActiveAgents()[4]] = tTest;
+ tactics[wm->kn->ActiveAgents()[5]] = tTest;
+ }
+ }
+ if(wm->gs == STATE_Halt){
+ for(int i = 0 ; i < wm->kn->ActiveAgents().size() ; i++){
+ tactics[i] = new TacticHalt(wm);
+ }
+ }
+ if(wm->gs == STATE_Free_kick_Opp){
+ tactics[wm->ref_goalie_our] = tTest;
+ }
+ if(wm->gs == STATE_Free_kick_Our){
+ tactics[0] = (Tactic*) (new TacticTest(wm));
+ }
+ for(int i=0;ikn->ActiveAgents().length();i++){
+ tactics[wm->kn->ActiveAgents()[i]] = tTest;
+ }
+ wm->debug_pos.clear();
+// if(wm->ball.isValid){
+// wm->debug_pos.append(wm->ball.pos.loc);
+// qDebug()<<"x :"<ball.pos.loc.x;
+// qDebug()<<"y :"<ball.pos.loc.y<<"\n\n";
+// }
}
+//Vector2D PlayTest2::generatePos(int radius,double alpha){
+// return Vector2D(wm->ball.pos.loc.x + radius*std::sin()
+//}
diff --git a/src/ai/play/playtest2.h b/src/ai/play/playtest2.h
old mode 100644
new mode 100755
index 1a5d002..f4e06b4
--- a/src/ai/play/playtest2.h
+++ b/src/ai/play/playtest2.h
@@ -3,6 +3,11 @@
#include "play.h"
#include "QDebug"
+<<<<<<< HEAD
+#include "tactic/tactichalt.h"
+=======
+#include
+>>>>>>> 4bde963eede2897a0748e0221474ee6c1450efde
class PlayTest2 : public Play
{
@@ -10,16 +15,14 @@ class PlayTest2 : public Play
public:
explicit PlayTest2(WorldModel *worldmodel, QObject *parent = 0);
virtual void execute();
- //virtual Tactic* getTactic(int id);
+ virtual void initRole();
virtual int enterCondition();
private:
- TacticGoalie* tGolie;
- TacticTestFriction* tTF;
- TacticHalt* thalt;
- TacticTest* tTest;
-
+ TacticTest2* tTest;
virtual void initRole();
+ TacticTest2* tTest;
+ int Parabola_intersection (Vector2D, Vector2D, double, Vector2D *, Vector2D *);
};
#endif // PLAYTEST2_H
diff --git a/src/ai/positioning.cpp b/src/ai/positioning.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/positioning.h b/src/ai/positioning.h
old mode 100644
new mode 100755
diff --git a/src/ai/robotcommand.h b/src/ai/robotcommand.h
old mode 100644
new mode 100755
diff --git a/src/ai/skill.cpp b/src/ai/skill.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/skill.h b/src/ai/skill.h
old mode 100644
new mode 100755
diff --git a/src/ai/skill/shootball.cpp b/src/ai/skill/shootball.cpp
new file mode 100755
index 0000000..d46d812
--- /dev/null
+++ b/src/ai/skill/shootball.cpp
@@ -0,0 +1,2 @@
+#include "shootball.h"
+
diff --git a/src/ai/skill/shootball.h b/src/ai/skill/shootball.h
new file mode 100755
index 0000000..42a85f9
--- /dev/null
+++ b/src/ai/skill/shootball.h
@@ -0,0 +1,22 @@
+#ifndef SHOOTBALL_H
+#define SHOOTBALL_H
+#include
+#include "skill.h"
+
+//class shootBall : public Skill
+//{
+// Q_OBJECT
+//public:
+// shootBall();
+// explicit shootBall(WorldModel* wm, QObject *parent = 0);
+// bool execute(RobotCommand& rc);
+//private:
+// bool targetMove;
+// Vector2D* _target;
+// /*!
+// is ball shooted or not.
+// */
+// bool ballShooted;
+//};
+
+#endif // SHOOTBALL_H
diff --git a/src/ai/skill/skillkick.cpp b/src/ai/skill/skillkick.cpp
old mode 100644
new mode 100755
index ce0e7f5..1341b7a
--- a/src/ai/skill/skillkick.cpp
+++ b/src/ai/skill/skillkick.cpp
@@ -8,116 +8,118 @@ SkillKick::SkillKick(WorldModel* wm, QObject *parent) :
bool SkillKick::execute(RobotCommand &rc)
{
- //locating behind the ball...
-
- Vector2D goal;
-
- Vector2D ball2target;
-
- ball2target=this->_Target - wm->ball.pos.loc;
-
- ball2target.setLength(ROBOT_RADIUS+8);
-
- goal=wm->ball.pos.loc - ball2target;
-
- // Vector2D checkingPoint;
-
- // ball2target.setLength(2*ROBOT_RADIUS+20);
-
- // checkingPoint=wm->ball.pos.loc - ball2target;
-
- // Segment2D *kicker2chekingPoint=new Segment2D(wm->ourRobot[index].pos.loc,checkingPoint);
-
- // Circle2D checkingCircle(wm->ball.pos.loc,ROBOT_RADIUS*2);
-
-
- Circle2D checkingCircle(wm->ball.pos.loc,ROBOT_RADIUS);
- Segment2D *kicker2goal=new Segment2D(wm->ourRobot[index].pos.loc,goal);
-
- if( checkingCircle.HasIntersection( *kicker2goal ) )
- {
- ball2target.setLength(200+200);
- Vector2D temp1=goal+(-ball2target).rotatedVector(60);
- Vector2D temp2=goal+(-ball2target).rotatedVector(-60);
- if((wm->ourRobot[index].pos.loc-temp1).length2()<(wm->ourRobot[index].pos.loc-temp2).length2())
- {
- goal=temp1;
- }
- else
- {
- goal=temp2;
- }
- }
-
- rc.fin_pos.loc=goal;
-
- rc.fin_pos.dir=ball2target.dir().radian();
-
-
-
-
- //kicking...
-
- if( wm->isSim )
- {
- //simulatuion
- Vector2D centerofrarecircle;
- ball2target.setLength(ROBOT_RADIUS+10);
- centerofrarecircle=wm->ball.pos.loc-ball2target;
- Circle2D rearCircle(centerofrarecircle,20);
- Circle2D ballCircle(wm->ball.pos.loc,ROBOT_RADIUS+50);
- if( wm->ball.isValid&&
- ballCircle.contains(wm->ourRobot[index].pos.loc)&&
- rearCircle.contains(wm->ourRobot[index].pos.loc)//&&
- // fabs((ball2target.dir().degree())-((wm->ourRobot[index].pos.dir)*180/M_PI))<3
- )
- {
- if( !isShoot )
- rc.kickspeedx = 3.5;
- else
- rc.kickspeedx = 8;
- }
- }
- else
- {
- // real:
-
- if( !wm->useShootSensor )
- {
- //without kicking sensor
- Vector2D centerofrarecircle;
- ball2target.setLength(ROBOT_RADIUS+10);
- centerofrarecircle=wm->ball.pos.loc-ball2target;
- Circle2D rearCircle(centerofrarecircle,20);
- Circle2D ballCircle(wm->ball.pos.loc,ROBOT_RADIUS+20);
- if( wm->ball.isValid&&
- ballCircle.contains(wm->ourRobot[index].pos.loc)&&
- rearCircle.contains(wm->ourRobot[index].pos.loc)//&&
- // fabs((ball2target.dir().degree())-((wm->ourRobot[index].pos.dir)*180/M_PI))<3
- )
- {
- if( !isShoot )
- rc.kickspeedx = 30;
- else
- rc.kickspeedx = 100;
- }
- }
- else
- {
- //with kicking sensor
- if( ((wm->ball.pos.loc-wm->ourRobot[index].pos.loc).length()<500) && (fabs((ball2target.dir().degree())-((wm->ourRobot[index].pos.dir)*180/M_PI))<90 || fabs((ball2target.dir().degree())-((wm->ourRobot[index].pos.dir)*180/M_PI))>270) )
- {
- if( !isShoot )
- rc.kickspeedx = 140;
- else
- rc.kickspeedx = 200;
- // if(passFlag)
- // {
- // rc.kickspeedx=sqrt(2*10*lossFactor*(this->_Target-wm->ourRobot[index].pos.loc).length());
- // }
- }
- }
- }
+/*cod khodam*/
+
+// //locating behind the ball...
+
+// Vector2D goal;
+
+// Vector2D ball2target;
+
+// ball2target=this->_Target - wm->ball.pos.loc;
+
+// ball2target.setLength(ROBOT_RADIUS+8);
+
+// goal=wm->ball.pos.loc - ball2target;
+
+// // Vector2D checkingPoint;
+
+// // ball2target.setLength(2*ROBOT_RADIUS+20);
+
+// // checkingPoint=wm->ball.pos.loc - ball2target;
+
+// // Segment2D *kicker2chekingPoint=new Segment2D(wm->ourRobot[index].pos.loc,checkingPoint);
+
+// // Circle2D checkingCircle(wm->ball.pos.loc,ROBOT_RADIUS*2);
+
+
+// Circle2D checkingCircle(wm->ball.pos.loc,ROBOT_RADIUS);
+// Segment2D *kicker2goal=new Segment2D(wm->ourRobot[index].pos.loc,goal);
+
+// if( checkingCircle.HasIntersection( *kicker2goal ) )
+// {
+// ball2target.setLength(200+200);
+// Vector2D temp1=goal+(-ball2target).rotatedVector(60);
+// Vector2D temp2=goal+(-ball2target).rotatedVector(-60);
+// if((wm->ourRobot[index].pos.loc-temp1).length2()<(wm->ourRobot[index].pos.loc-temp2).length2())
+// {
+// goal=temp1;
+// }
+// else
+// {
+// goal=temp2;
+// }
+// }
+
+// rc.fin_pos.loc=goal;
+
+// rc.fin_pos.dir=ball2target.dir().radian();
+
+
+
+
+// //kicking...
+
+// if( wm->isSim )
+// {
+// //simulatuion
+// Vector2D centerofrarecircle;
+// ball2target.setLength(ROBOT_RADIUS+10);
+// centerofrarecircle=wm->ball.pos.loc-ball2target;
+// Circle2D rearCircle(centerofrarecircle,20);
+// Circle2D ballCircle(wm->ball.pos.loc,ROBOT_RADIUS+50);
+// if( wm->ball.isValid&&
+// ballCircle.contains(wm->ourRobot[index].pos.loc)&&
+// rearCircle.contains(wm->ourRobot[index].pos.loc)//&&
+// // fabs((ball2target.dir().degree())-((wm->ourRobot[index].pos.dir)*180/M_PI))<3
+// )
+// {
+// if( !isShoot )
+// rc.kickspeedx = 3.5;
+// else
+// rc.kickspeedx = 8;
+// }
+// }
+// else
+// {
+// // real:
+
+// if( !wm->useShootSensor )
+// {
+// //without kicking sensor
+// Vector2D centerofrarecircle;
+// ball2target.setLength(ROBOT_RADIUS+10);
+// centerofrarecircle=wm->ball.pos.loc-ball2target;
+// Circle2D rearCircle(centerofrarecircle,20);
+// Circle2D ballCircle(wm->ball.pos.loc,ROBOT_RADIUS+20);
+// if( wm->ball.isValid&&
+// ballCircle.contains(wm->ourRobot[index].pos.loc)&&
+// rearCircle.contains(wm->ourRobot[index].pos.loc)//&&
+// // fabs((ball2target.dir().degree())-((wm->ourRobot[index].pos.dir)*180/M_PI))<3
+// )
+// {
+// if( !isShoot )
+// rc.kickspeedx = 30;
+// else
+// rc.kickspeedx = 100;
+// }
+// }
+// else
+// {
+// //with kicking sensor
+// if( ((wm->ball.pos.loc-wm->ourRobot[index].pos.loc).length()<500) && (fabs((ball2target.dir().degree())-((wm->ourRobot[index].pos.dir)*180/M_PI))<90 || fabs((ball2target.dir().degree())-((wm->ourRobot[index].pos.dir)*180/M_PI))>270) )
+// {
+// if( !isShoot )
+// rc.kickspeedx = 140;
+// else
+// rc.kickspeedx = 200;
+// // if(passFlag)
+// // {
+// // rc.kickspeedx=sqrt(2*10*lossFactor*(this->_Target-wm->ourRobot[index].pos.loc).length());
+// // }
+// }
+// }
+// }
}
diff --git a/src/ai/skill/skillkick.cpp.autosave b/src/ai/skill/skillkick.cpp.autosave
new file mode 100755
index 0000000..c2dff8c
--- /dev/null
+++ b/src/ai/skill/skillkick.cpp.autosave
@@ -0,0 +1,1598 @@
+#include "skillkick.h"
+
+SkillKick::SkillKick(WorldModel* wm, QObject *parent) :
+ Skill(wm, parent)
+{
+ isShoot = true;
+}
+
+bool SkillKick::
+execute(RobotCommand &rc)
+{
+/*cod khodam*/
+
+// //locating behind the ball...
+
+// Vector2D goal;
+
+// Vector2D ball2target;
+
+// ball2target=this->_Target - wm->ball.pos.loc;
+
+// ball2target.setLength(ROBOT_RADIUS+8);
+
+// goal=wm->ball.pos.loc - ball2target;
+
+// // Vector2D checkingPoint;
+
+// // ball2target.setLength(2*ROBOT_RADIUS+20);
+
+// // checkingPoint=wm->ball.pos.loc - ball2target;
+
+// // Segment2D *kicker2chekingPoint=new Segment2D(wm->ourRobot[index].pos.loc,checkingPoint);
+
+// // Circle2D checkingCircle(wm->ball.pos.loc,ROBOT_RADIUS*2);
+
+
+// Circle2D checkingCircle(wm->ball.pos.loc,ROBOT_RADIUS);
+// Segment2D *kicker2goal=new Segment2D(wm->ourRobot[index].pos.loc,goal);
+
+// if( checkingCircle.HasIntersection( *kicker2goal ) )
+// {
+// ball2target.setLength(200+200);
+// Vector2D temp1=goal+(-ball2target).rotatedVector(60);
+// Vector2D temp2=goal+(-ball2target).rotatedVector(-60);
+// if((wm->ourRobot[index].pos.loc-temp1).length2()<(wm->ourRobot[index].pos.loc-temp2).length2())
+// {
+// goal=temp1;
+// }
+// else
+// {
+// goal=temp2;
+// }
+// }
+
+// rc.fin_pos.loc=goal;
+
+// rc.fin_pos.dir=ball2target.dir().radian();
+
+
+
+
+// //kicking...
+
+// if( wm->isSim )
+// {
+// //simulatuion
+// Vector2D centerofrarecircle;
+// ball2target.setLength(ROBOT_RADIUS+10);
+// centerofrarecircle=wm->ball.pos.loc-ball2target;
+// Circle2D rearCircle(centerofrarecircle,20);
+// Circle2D ballCircle(wm->ball.pos.loc,ROBOT_RADIUS+50);
+// if( wm->ball.isValid&&
+// ballCircle.contains(wm->ourRobot[index].pos.loc)&&
+// rearCircle.contains(wm->ourRobot[index].pos.loc)//&&
+// // fabs((ball2target.dir().degree())-((wm->ourRobot[index].pos.dir)*180/M_PI))<3
+// )
+// {
+// if( !isShoot )
+// rc.kickspeedx = 3.5;
+// else
+// rc.kickspeedx = 8;
+// }
+// }
+// else
+// {
+// // real:
+
+// if( !wm->useShootSensor )
+// {
+// //without kicking sensor
+// Vector2D centerofrarecircle;
+// ball2target.setLength(ROBOT_RADIUS+10);
+// centerofrarecircle=wm->ball.pos.loc-ball2target;
+// Circle2D rearCircle(centerofrarecircle,20);
+// Circle2D ballCircle(wm->ball.pos.loc,ROBOT_RADIUS+20);
+// if( wm->ball.isValid&&
+// ballCircle.contains(wm->ourRobot[index].pos.loc)&&
+// rearCircle.contains(wm->ourRobot[index].pos.loc)//&&
+// // fabs((ball2target.dir().degree())-((wm->ourRobot[index].pos.dir)*180/M_PI))<3
+// )
+// {
+// if( !isShoot )
+// rc.kickspeedx = 30;
+// else
+// rc.kickspeedx = 100;
+// }
+// }
+// else
+// {
+// //with kicking sensor
+// if( ((wm->ball.pos.loc-wm->ourRobot[index].pos.loc).length()<500) && (fabs((ball2target.dir().degree())-((wm->ourRobot[index].pos.dir)*180/M_PI))<90 || fabs((ball2target.dir().degree())-((wm->ourRobot[index].pos.dir)*180/M_PI))>270) )
+// {
+// if( !isShoot )
+// rc.kickspeedx = 140;
+// else
+// rc.kickspeedx = 200;
+// // if(passFlag)
+// // {
+// // rc.kickspeedx=sqrt(2*10*lossFactor*(this->_Target-wm->ourRobot[index].pos.loc).length());
+// // }
+// }
+// }
+// }
+
+}
+
+
+
+
+
+
+
+
+// Vector2D S=wm->oppRobot[0].pos.loc-target;//-wm->oppRobot[0].pos.loc;
+// S.setDir(wm->ourRobot[0].pos.dir*(180/M_PI));
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+// // // 1 && 2
+
+//// if(wm->ball.vel.loc.length()<0.05)
+//// {
+//// if((wm->ball.pos.loc-wm->ourRobot[0].pos.loc).length2()>(wm->ball.pos.loc-wm->ourRobot[1].pos.loc).length2())
+//// {
+//// kicker0=false;
+//// receiver0=true;
+
+//// kicker1=true;
+//// receiver1=false;
+//// }
+
+//// else if((wm->ball.pos.loc-wm->ourRobot[0].pos.loc).length2()<(wm->ball.pos.loc-wm->ourRobot[1].pos.loc).length2())
+//// {
+//// kicker0=true;
+//// receiver0=false;
+
+//// kicker1=false;
+//// receiver1=true;
+//// }
+
+
+//// }
+
+
+
+
+//// if(index==0)
+//// {
+//// if(kicker0)
+//// {
+//// //locating behind the ball...
+
+//// Vector2D ball2target;
+
+
+
+//// Vector2D target=wm->ourRobot[1].pos.loc;//{2470,0};
+
+//// ball2target=target-wm->ball.pos.loc;
+
+//// ball2target.setLength(95);
+
+
+//// rc.fin_pos.loc=wm->ball.pos.loc - ball2target;
+
+//// rc.fin_pos.dir=ball2target.dir().radian();
+
+
+
+//// ///////////////////////////////////////////////////////////////////////////////////////////////////////////////
+
+//// // kicking
+
+//// if( wm->isSim )
+//// {
+//// //simulation:
+//// Vector2D A;
+//// ball2target.setLength(115);
+//// A=wm->ball.pos.loc-ball2target;
+//// Circle2D C2(A,120);
+//// Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+20);
+//// if( wm->ball.isValid&&
+//// C.contains(wm->ourRobot[index].pos.loc)&&
+//// C2.contains(wm->ourRobot[index].pos.loc)&&
+//// (fabs(((wm->ourRobot[1].pos.loc-wm->ourRobot[index].pos.loc).dir().degree())-(ball2target.dir().degree())<10))
+//// )
+//// {
+//// rc.kickspeedx=5;
+//// receiver0=false;
+//// kicker0=false;
+
+//// }
+//// }
+//// else
+//// {
+//// //real:
+//// Vector2D A;
+//// vec2goal.setLength(115);
+//// A=wm->ball.pos.loc-vec2goal;
+//// Circle2D C2(A,120);
+//// Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+15);
+//// if( wm->ball.isValid&&
+//// C.contains(wm->ourRobot[0].pos.loc)&&
+//// C2.contains(wm->ourRobot[0].pos.loc)
+//// )
+//// {
+//// rc.kickspeedx=10;
+//// }
+//// }
+//// }
+
+//// else if(receiver0)
+//// {
+//RecievingPass
+
+
+// Vector2D robot2ball=wm->ball.pos.loc-wm->ourRobot[index].pos.loc;
+// rc.fin_pos.dir=robot2ball.dir().radian();
+
+// rc.fin_pos.loc=wm->ourRobot[index].pos.loc;//{0,0};
+// //rc.maxSpeed=3;
+
+
+// if (wm->ball.vel.loc.length()>0.1)
+// {
+// Vector2D goal;
+// Vector2D Ballpos=wm->ball.pos.loc;
+// Ball2C = new Line2D(Ballpos , wm->ball.vel.loc.dir().degree());
+// Vector2D A,B;
+
+// ballvel.setDir(wm->ball.vel.loc.dir().degree());
+
+
+// if(fabs(ballvel.dir().degree()-last_ballvel.dir().degree())>10)
+// {
+
+// C0.assign(wm->ourRobot[0].pos.loc,ROBOT_RADIUS+500);
+
+// }
+
+// last_ballvel.setDir(ballvel.dir().degree());
+
+
+
+// C0.intersection(*Ball2C,&A,&B);
+
+// if( C0.HasIntersection(*Ball2C))
+// {
+
+// if((Ballpos-A).length2()>(Ballpos-B).length2())
+// {
+// goal=A;
+// }
+
+// else
+// {
+// goal=B;
+// }
+
+// rc.fin_pos.loc=goal;
+// rc.fin_pos.dir=(wm->ball.vel.loc.dir().radian()+M_PI);//tttarget.dir().radian();//
+
+
+// }
+
+
+
+// }
+// ////////////////////////////////////////////////////////////////////////////////
+// //change decision
+// //Circle2D CD(wm->ourRobot[index].pos.loc,C0.radius()+300);
+// if((wm->ourRobot[index].pos.loc-wm->ball.pos.loc).length()<150)
+// {
+// kicker0=true;
+// receiver0=false;
+
+// kicker1=false;
+// receiver1=true;
+// }
+
+//// /////////////////////////////////////////////////////////////////////////////////
+//// }
+
+
+//// else if(!kicker0 && !receiver0)//kicker no!!!! receiver no!!!>>>>....
+//// {
+//// Vector2D robot2ball=wm->ball.pos.loc-wm->ourRobot[index].pos.loc;
+//// rc.fin_pos.dir=robot2ball.dir().radian();
+
+//// rc.fin_pos.loc=wm->ourRobot[index].pos.loc;//{0,0};
+//// }
+
+//// }
+
+// else if(index==1)
+// {
+// if(kicker1)
+// {
+// //locating behind the ball...
+
+// Vector2D ball2target;
+
+
+// Vector2D target=wm->ourRobot[0].pos.loc;//{2470,0};
+
+// ball2target=target-wm->ball.pos.loc;
+
+// ball2target.setLength(95);
+
+
+
+// rc.fin_pos.loc=wm->ball.pos.loc - ball2target;
+
+// rc.fin_pos.dir=ball2target.dir().radian();
+
+
+
+///////////////////////////////////////////////////////////////////////////////////////////////////////////////
+
+// kicking
+
+
+//real:
+// Vector2D A;
+// vec2goal.setLength(115);
+// A=wm->ball.pos.loc-vec2goal;
+// Circle2D C2(A,120);
+// Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+15);
+// if( wm->ball.isValid&&
+// C.contains(wm->ourRobot[0].pos.loc)&&
+// C2.contains(wm->ourRobot[0].pos.loc)
+// )
+// {
+// rc.kickspeedx=10;
+// }
+
+
+
+// //simulation:
+// Vector2D A;
+// ball2target.setLength(115);
+// A=wm->ball.pos.loc-ball2target;
+// Circle2D C2(A,120);
+// Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+20);
+// if( wm->ball.isValid&&
+// C.contains(wm->ourRobot[index].pos.loc)&&
+// C2.contains(wm->ourRobot[index].pos.loc)&&
+// (fabs(((wm->ourRobot[0].pos.loc-wm->ourRobot[index].pos.loc).dir().degree())-(ball2target.dir().degree())<5))
+// )
+
+// {
+// //qDebug()<<","<ourRobot[0].pos.loc-wm->ourRobot[index].pos.loc).dir().degree())-(ball2target.dir().degree()));
+// rc.kickspeedx=5;
+// kicker1=false;
+// receiver1=false;
+
+// }
+// }
+
+
+// else if(receiver1)
+// {
+// //RecievingPass
+
+// //rc.maxSpeed=2;
+
+
+// Vector2D robot2ball=wm->ball.pos.loc-wm->ourRobot[index].pos.loc;
+// rc.fin_pos.dir=robot2ball.dir().radian();
+
+// rc.fin_pos.loc=wm->ourRobot[index].pos.loc;//{0,0};//
+
+
+// if (wm->ball.vel.loc.length()>0.1)
+// {
+// Vector2D goal;
+// Vector2D Ballpos=wm->ball.pos.loc;
+// Ball2C = new Line2D(Ballpos , wm->ball.vel.loc.dir().degree());
+// Vector2D A,B;
+
+// ballvel.setDir(wm->ball.vel.loc.dir().degree());
+
+
+// if(fabs(ballvel.dir().degree()-last_ballvel.dir().degree())>10)
+// {
+
+// C1.assign(wm->ourRobot[index].pos.loc,ROBOT_RADIUS+500);
+
+// }
+
+// last_ballvel.setDir(ballvel.dir().degree());
+
+
+
+// C1.intersection(*Ball2C,&A,&B);
+
+// if( C1.HasIntersection(*Ball2C))
+// {
+// if((Ballpos-A).length2()>(Ballpos-B).length2())
+// {
+// goal=A;
+// }
+
+// else
+// {
+// goal=B;
+// }
+
+// rc.fin_pos.loc=goal;
+// rc.fin_pos.dir=(wm->ball.vel.loc.dir().radian()+M_PI);
+
+
+// }
+
+
+
+// }
+
+// ////////////////////////////////////////////////////////////////////////////////
+// //change decision
+// //Circle2D CD(wm->ourRobot[index].pos.loc,100);
+// if((wm->ourRobot[index].pos.loc-wm->ball.pos.loc).length()<150)
+// {
+
+
+// kicker0=false;
+// receiver0=true;
+
+// kicker1=true;
+// receiver1=false;
+// }
+
+// /////////////////////////////////////////////////////////////////////////////////
+
+
+// }
+
+
+
+// else if(!kicker1 && !receiver1)//kicker no!!!! receiver no!!!>>>>....
+// {
+// Vector2D robot2ball=wm->ball.pos.loc-wm->ourRobot[index].pos.loc;
+// rc.fin_pos.dir=robot2ball.dir().radian();
+
+// rc.fin_pos.loc=wm->ourRobot[index].pos.loc;//{0,0};
+// }
+
+// }
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+// //......WON touch.....
+
+
+
+
+// if(index==0)
+// {
+// if(true)
+// {
+
+// //locating behind the ball...
+
+// Vector2D ball2target;
+
+// Vector2D target=wm->ourRobot[1].pos.loc;//{2470,0};
+
+// ball2target=target-wm->ball.pos.loc;
+
+// ball2target.setLength(95);
+
+// rc.fin_pos.loc=wm->ball.pos.loc - ball2target;
+
+// rc.fin_pos.dir=ball2target.dir().radian();
+
+
+
+
+
+// // kicking
+
+// //simulation:
+// Vector2D A;
+// ball2target.setLength(115);
+// A=wm->ball.pos.loc-ball2target;
+// Circle2D C2(A,120);
+// Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+20);
+// if( wm->ball.isValid&&
+// C.contains(wm->ourRobot[index].pos.loc)&&
+// C2.contains(wm->ourRobot[index].pos.loc)&&
+// (fabs(((wm->ourRobot[1].pos.loc-wm->ourRobot[index].pos.loc).dir().degree())-(ball2target.dir().degree())<3))
+// )
+// {
+// rc.kickspeedx=5;
+// }
+
+
+
+
+
+// }
+
+
+// }
+
+
+
+
+
+// if(index==1)
+// {
+
+
+
+// // qDebug()<ourRobot[index].pos.dir;
+
+
+// if(true)
+// {
+
+// //locating in the safe position to recieve the pass
+
+// rc.maxSpeed=3;
+
+
+// Vector2D target={-3000,0};
+
+// Vector2D robot2target=target-wm->ourRobot[index].pos.loc;
+// rc.fin_pos.dir=robot2target.dir().radian();
+
+// rc.fin_pos.loc=wm->ourRobot[index].pos.loc;//{0,0};//
+
+
+// if (wm->ball.vel.loc.length()>0.1)
+// {
+// Vector2D goal;
+// Vector2D Ballpos=wm->ball.pos.loc;
+// Ball2C = new Line2D(Ballpos , wm->ball.vel.loc.dir().degree());
+// Vector2D A,B;
+
+// ballvel.setDir(wm->ball.vel.loc.dir().degree());
+
+
+// if(fabs(ballvel.dir().degree()-last_ballvel.dir().degree())>10)
+// {
+
+// C1.assign(wm->ourRobot[index].pos.loc,ROBOT_RADIUS+500);
+
+// }
+
+// last_ballvel.setDir(ballvel.dir().degree());
+
+
+
+// C1.intersection(*Ball2C,&A,&B);
+
+// if( C1.HasIntersection(*Ball2C))
+// {
+// if((Ballpos-A).length2()>(Ballpos-B).length2())
+// {
+// goal=A;
+// }
+
+// else
+// {
+// goal=B;
+// }
+
+// rc.fin_pos.loc=goal;
+
+
+// }
+
+// }
+
+
+
+// //simulation:
+
+// Vector2D ball2target;
+
+// target={-3000,0};//wm->ourRobot[1].pos.loc;//
+// ball2target=target-wm->ball.pos.loc;
+
+
+
+
+// Vector2D A;
+// ball2target.setLength(115);
+// A=wm->ball.pos.loc-ball2target;
+// Circle2D C2(A,120);
+// Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+20);
+// if(
+// wm->ball.isValid&&
+// C.contains(wm->ourRobot[index].pos.loc)&&
+// C2.contains(wm->ourRobot[index].pos.loc)&&
+// (fabs(((target-wm->ourRobot[index].pos.loc).dir().radian())-(wm->ourRobot[index].pos.dir))<0.02*M_PI)
+// )
+
+// {
+
+
+
+// rc.kickspeedx=10;
+
+// }
+
+
+
+// }
+
+
+// }
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+// // // 1 && 2 && 3
+
+// // if(wm->ball.vel.loc.length()<0.05)
+// // {
+// //// if((wm->ball.pos.loc-wm->ourRobot[0].pos.loc).length2()>(wm->ball.pos.loc-wm->ourRobot[1].pos.loc).length2())
+// //// {
+// //// kicker0=false;
+// //// receiver0=true;
+
+// //// kicker1=true;
+// //// receiver1=false;
+// //// }
+
+// //// else if((wm->ball.pos.loc-wm->ourRobot[0].pos.loc).length2()<(wm->ball.pos.loc-wm->ourRobot[1].pos.loc).length2())
+// //// {
+// //// kicker0=true;
+// //// receiver0=false;
+
+// //// kicker1=false;
+// //// receiver1=true;
+// //// }
+
+
+// // kicker0=true;
+// // receiver0=false;
+
+// // kicker1=false;
+// // receiver1=true;
+
+// // kicker2=false;
+// // receiver2=false;
+
+
+
+
+// // }
+
+
+
+
+// // if(index==0)
+// // {
+// // if(kicker0)
+// // {
+// // //locating behind the ball...
+
+// // Vector2D ball2target;
+
+// // Vector2D target=wm->ourRobot[1].pos.loc;//{2470,0};
+
+// // ball2target=target-wm->ball.pos.loc;
+
+// // ball2target.setLength(95);
+
+// // rc.fin_pos.loc=wm->ball.pos.loc - ball2target;
+
+// // rc.fin_pos.dir=ball2target.dir().radian();
+
+// // ///////////////////////////////////////////////////////////////////////////////////////////////////////////////
+
+// // // kicking
+
+
+// // //real:
+// // // Vector2D A;
+// // // vec2goal.setLength(115);
+// // // A=wm->ball.pos.loc-vec2goal;
+// // // Circle2D C2(A,120);
+// // // Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+15);
+// // // if( wm->ball.isValid&&
+// // // C.contains(wm->ourRobot[0].pos.loc)&&
+// // // C2.contains(wm->ourRobot[0].pos.loc)
+// // // )
+// // // {
+// // // rc.kickspeedx=10;
+// // // }
+
+
+
+// // //simulation:
+// // Vector2D A;
+// // ball2target.setLength(115);
+// // A=wm->ball.pos.loc-ball2target;
+// // Circle2D C2(A,120);
+// // Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+20);
+// // if( wm->ball.isValid&&
+// // C.contains(wm->ourRobot[index].pos.loc)&&
+// // C2.contains(wm->ourRobot[index].pos.loc)&&
+// // (fabs(((wm->ourRobot[1].pos.loc-wm->ourRobot[index].pos.loc).dir().degree())-(ball2target.dir().degree())<10))
+// // )
+// // {
+// // rc.kickspeedx=5;
+// // receiver0=false;
+// // kicker0=false;
+
+// // }
+
+
+// // }
+
+// // else if(receiver0)
+// // {
+// // //RecievingPass
+
+
+// // Vector2D ball2target;
+// // Vector2D target=wm->ourRobot[1].pos.loc;//{2470,0};
+// // ball2target=target-wm->ball.pos.loc;
+// // Vector2D robot2ball=wm->ball.pos.loc-wm->ourRobot[index].pos.loc;
+
+
+// // //rc.fin_pos.dir=robot2ball.dir().radian();
+
+// // rc.fin_pos.dir=ball2target.dir().radian();
+
+// // rc.fin_pos.loc=wm->ourRobot[index].pos.loc;//{0,0};
+// // //rc.maxSpeed=3;
+
+
+// // if (wm->ball.vel.loc.length()>0.1)
+// // {
+// // Vector2D goal;
+// // Vector2D Ballpos=wm->ball.pos.loc;
+// // Ball2C = new Line2D(Ballpos , wm->ball.vel.loc.dir().degree());
+// // Vector2D A,B;
+
+// // ballvel.setDir(wm->ball.vel.loc.dir().degree());
+
+
+// // if(fabs(ballvel.dir().degree()-last_ballvel.dir().degree())>10)
+// // {
+
+// // C0.assign(wm->ourRobot[0].pos.loc,ROBOT_RADIUS+500);
+
+// // }
+
+// // last_ballvel.setDir(ballvel.dir().degree());
+
+
+
+// // C0.intersection(*Ball2C,&A,&B);
+
+// // if( C0.HasIntersection(*Ball2C))
+// // {
+
+// // if((Ballpos-A).length2()>(Ballpos-B).length2())
+// // {
+// // goal=A;
+// // }
+
+// // else
+// // {
+// // goal=B;
+// // }
+
+// // rc.fin_pos.loc=goal;
+// // rc.fin_pos.dir=(wm->ball.vel.loc.dir().radian()+M_PI);//tttarget.dir().radian();//
+
+
+// // }
+
+
+
+// // }
+// // ////////////////////////////////////////////////////////////////////////////////
+// // //change decision
+// // //Circle2D CD(wm->ourRobot[index].pos.loc,C0.radius()+300);
+// // if((wm->ourRobot[index].pos.loc-wm->ball.pos.loc).length()<300)
+// // {
+// // kicker0=true;
+// // receiver0=false;
+
+// // kicker1=false;
+// // receiver1=true;
+
+// // kicker2=false;
+// // receiver2=false;
+// // }
+
+// // /////////////////////////////////////////////////////////////////////////////////
+// // }
+
+
+// // else if(!kicker0 && !receiver0)//kicker no!!!! receiver no!!!>>>>....
+// // {
+// // Vector2D robot2ball=wm->ball.pos.loc-wm->ourRobot[index].pos.loc;
+// // rc.fin_pos.dir=robot2ball.dir().radian();
+
+// // rc.fin_pos.loc=wm->ourRobot[index].pos.loc;//{0,0};
+// // }
+
+// // }
+
+// // else if(index==1)
+// // {
+// // if(kicker1)
+// // {
+// // //locating behind the ball...
+
+// // Vector2D ball2target;
+
+// // Vector2D target=wm->ourRobot[2].pos.loc;//{2470,0};
+
+// // ball2target=target-wm->ball.pos.loc;
+
+// // ball2target.setLength(95);
+
+// // rc.fin_pos.loc=wm->ball.pos.loc - ball2target;
+
+// // rc.fin_pos.dir=ball2target.dir().radian();
+
+// // ///////////////////////////////////////////////////////////////////////////////////////////////////////////////
+
+// // // kicking
+
+
+// // //real:
+// // // Vector2D A;
+// // // vec2goal.setLength(115);
+// // // A=wm->ball.pos.loc-vec2goal;
+// // // Circle2D C2(A,120);
+// // // Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+15);
+// // // if( wm->ball.isValid&&
+// // // C.contains(wm->ourRobot[0].pos.loc)&&
+// // // C2.contains(wm->ourRobot[0].pos.loc)
+// // // )
+// // // {
+// // // rc.kickspeedx=10;
+// // // }
+
+
+
+// // //simulation:
+// // Vector2D A;
+// // ball2target.setLength(115);
+// // A=wm->ball.pos.loc-ball2target;
+// // Circle2D C2(A,120);
+// // Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+20);
+// // if( wm->ball.isValid&&
+// // C.contains(wm->ourRobot[index].pos.loc)&&
+// // C2.contains(wm->ourRobot[index].pos.loc)&&
+// // (fabs(((wm->ourRobot[2].pos.loc-wm->ourRobot[index].pos.loc).dir().degree())-(ball2target.dir().degree())<5))
+// // )
+
+// // {
+// // rc.kickspeedx=5;
+// // kicker1=false;
+// // receiver1=false;
+
+// // }
+// // }
+
+
+// // else if(receiver1)
+// // {
+// // //RecievingPass
+
+// // //rc.maxSpeed=2;
+
+// // Vector2D ball2target;
+// // Vector2D target=wm->ourRobot[0].pos.loc;//{2470,0};
+// // ball2target=target-wm->ball.pos.loc;
+// // Vector2D robot2ball=wm->ball.pos.loc-wm->ourRobot[index].pos.loc;
+// // //rc.fin_pos.dir=robot2ball.dir().radian();
+
+// // rc.fin_pos.loc=wm->ourRobot[index].pos.loc;//{0,0};//
+
+// // rc.fin_pos.dir=robot2ball.dir().radian();
+
+
+// // if (wm->ball.vel.loc.length()>0.1)
+// // {
+// // Vector2D goal;
+// // Vector2D Ballpos=wm->ball.pos.loc;
+// // Ball2C = new Line2D(Ballpos , wm->ball.vel.loc.dir().degree());
+// // Vector2D A,B;
+
+// // ballvel.setDir(wm->ball.vel.loc.dir().degree());
+
+
+// // if(fabs(ballvel.dir().degree()-last_ballvel.dir().degree())>10)
+// // {
+
+// // C1.assign(wm->ourRobot[index].pos.loc,ROBOT_RADIUS+500);
+
+// // }
+
+// // last_ballvel.setDir(ballvel.dir().degree());
+
+
+
+// // C1.intersection(*Ball2C,&A,&B);
+
+// // if( C1.HasIntersection(*Ball2C))
+// // {
+// // if((Ballpos-A).length2()>(Ballpos-B).length2())
+// // {
+// // goal=A;
+// // }
+
+// // else
+// // {
+// // goal=B;
+// // }
+
+// // rc.fin_pos.loc=goal;
+// // rc.fin_pos.dir=(wm->ball.vel.loc.dir().radian()+M_PI);
+
+
+// // }
+
+
+
+// // }
+
+// // ////////////////////////////////////////////////////////////////////////////////
+// // //change decision
+// // //Circle2D CD(wm->ourRobot[index].pos.loc,100);
+// // if((wm->ourRobot[index].pos.loc-wm->ball.pos.loc).length()<300)
+// // {
+// // kicker0=false;
+// // receiver0=false;
+
+// // kicker1=true;
+// // receiver1=false;
+
+// // kicker2=false;
+// // receiver2=true;
+// // }
+
+// // /////////////////////////////////////////////////////////////////////////////////
+
+
+// // }
+
+
+
+// // else if(!kicker1 && !receiver1)//kicker no!!!! receiver no!!!>>>>....
+// // {
+// // Vector2D robot2ball=wm->ball.pos.loc-wm->ourRobot[index].pos.loc;
+// // rc.fin_pos.dir=robot2ball.dir().radian();
+
+// // rc.fin_pos.loc=wm->ourRobot[index].pos.loc;//{0,0};
+// // }
+
+// // }
+
+
+
+
+
+// // else if(index==2)
+// // {
+// // if(kicker2)
+// // {
+// // //locating behind the ball...
+
+// // Vector2D ball2target;
+
+// // Vector2D target=wm->ourRobot[0].pos.loc;//{2470,0};
+
+// // ball2target=target-wm->ball.pos.loc;
+
+// // ball2target.setLength(95);
+
+// // rc.fin_pos.loc=wm->ball.pos.loc - ball2target;
+
+// // rc.fin_pos.dir=ball2target.dir().radian();
+
+// // ///////////////////////////////////////////////////////////////////////////////////////////////////////////////
+
+// // // kicking
+
+
+// // //real:
+// // // Vector2D A;
+// // // vec2goal.setLength(115);
+// // // A=wm->ball.pos.loc-vec2goal;
+// // // Circle2D C2(A,120);
+// // // Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+15);
+// // // if( wm->ball.isValid&&
+// // // C.contains(wm->ourRobot[0].pos.loc)&&
+// // // C2.contains(wm->ourRobot[0].pos.loc)
+// // // )
+// // // {
+// // // rc.kickspeedx=10;
+// // // }
+
+
+
+// // //simulation:
+// // Vector2D A;
+// // ball2target.setLength(115);
+// // A=wm->ball.pos.loc-ball2target;
+// // Circle2D C2(A,120);
+// // Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+20);
+// // if( wm->ball.isValid&&
+// // C.contains(wm->ourRobot[index].pos.loc)&&
+// // C2.contains(wm->ourRobot[index].pos.loc)&&
+// // (fabs(((wm->ourRobot[0].pos.loc-wm->ourRobot[index].pos.loc).dir().degree())-(ball2target.dir().degree())<5))
+// // )
+
+// // {
+// // rc.kickspeedx=5;
+// // kicker2=false;
+// // receiver2=false;
+
+// // }
+// // }
+
+
+// // else if(receiver2)
+// // {
+// // //RecievingPass
+
+// // //rc.maxSpeed=2;
+
+
+// // Vector2D ball2target;
+// // Vector2D target=wm->ourRobot[0].pos.loc;//{2470,0};
+// // ball2target=target-wm->ball.pos.loc;
+
+
+// // Vector2D robot2ball=wm->ball.pos.loc-wm->ourRobot[index].pos.loc;
+// // //rc.fin_pos.dir=robot2ball.dir().radian();
+
+// // rc.fin_pos.dir=robot2ball.dir().radian();
+
+// // rc.fin_pos.loc=wm->ourRobot[index].pos.loc;//{0,0};//
+
+
+// // if (wm->ball.vel.loc.length()>0.1)
+// // {
+// // Vector2D goal;
+// // Vector2D Ballpos=wm->ball.pos.loc;
+// // Ball2C = new Line2D(Ballpos , wm->ball.vel.loc.dir().degree());
+// // Vector2D A,B;
+
+// // ballvel.setDir(wm->ball.vel.loc.dir().degree());
+
+
+// // if(fabs(ballvel.dir().degree()-last_ballvel.dir().degree())>10)
+// // {
+
+// // C1.assign(wm->ourRobot[index].pos.loc,ROBOT_RADIUS+500);
+
+// // }
+
+// // last_ballvel.setDir(ballvel.dir().degree());
+
+
+
+// // C1.intersection(*Ball2C,&A,&B);
+
+// // if( C1.HasIntersection(*Ball2C))
+// // {
+// // if((Ballpos-A).length2()>(Ballpos-B).length2())
+// // {
+// // goal=A;
+// // }
+
+// // else
+// // {
+// // goal=B;
+// // }
+
+// // rc.fin_pos.loc=goal;
+// // rc.fin_pos.dir=(wm->ball.vel.loc.dir().radian()+M_PI);
+
+
+// // }
+
+
+
+// // }
+
+// // ////////////////////////////////////////////////////////////////////////////////
+// // //change decision
+// // //Circle2D CD(wm->ourRobot[index].pos.loc,100);
+// // if((wm->ourRobot[index].pos.loc-wm->ball.pos.loc).length()<300)
+// // {
+// // kicker0=false;
+// // receiver0=true;
+
+// // kicker1=false;
+// // receiver1=false;
+
+// // kicker2=true;
+// // receiver2=false;
+// // }
+
+// // /////////////////////////////////////////////////////////////////////////////////
+
+
+// // }
+
+
+
+// // else if(!kicker2 && !receiver2)//kicker no!!!! receiver no!!!>>>>....
+// // {
+// // Vector2D robot2ball=wm->ball.pos.loc-wm->ourRobot[index].pos.loc;
+// // rc.fin_pos.dir=robot2ball.dir().radian();
+
+// // rc.fin_pos.loc=wm->ourRobot[index].pos.loc;//{0,0};
+// // }
+
+// // }
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+// // /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////*
+
+// // //locating behind the ball...
+
+// // Vector2D vec2goal;
+
+// // Vector2D target=wm->ourRobot[1].pos.loc;//{2470,0};
+
+// // vec2goal=target-wm->ball.pos.loc;
+
+// // vec2goal.setLength(95);
+
+// // rc.fin_pos.loc=wm->ball.pos.loc - vec2goal;
+
+// // rc.fin_pos.dir=vec2goal.dir().radian();
+
+
+// // /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////*
+// //// Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+25);
+// //// if( C.contains(wm->ourRobot[0].pos.loc) && ( (wm->ourRobot[0].pos.loc-target).length2()>(wm->ball.pos.loc-target).length2() )
+// //// )
+// //// {
+// //// rc.kickspeedx=3;
+// //// }
+
+// // //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////*
+
+// // //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////**
+// //// kicking
+// // //real:
+// // // Vector2D A;
+// // // vec2goal.setLength(115);
+// // // A=wm->ball.pos.loc-vec2goal;
+// // // Circle2D C2(A,120);
+// // // Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+15);
+// // // if( wm->ball.isValid&&
+// // // C.contains(wm->ourRobot[0].pos.loc)&&
+// // // C2.contains(wm->ourRobot[0].pos.loc)
+// // // )
+// // // {
+// // // rc.kickspeedx=10;
+// // // }
+
+
+
+// // //simulation:
+// // Vector2D A;
+// // vec2goal.setLength(107);
+// // A=wm->ball.pos.loc-vec2goal;
+// // Circle2D C2(A,120);
+// // Circle2D C(wm->ball.pos.loc,ROBOT_RADIUS+20);
+// // if( wm->ball.isValid&&
+// // C.contains(wm->ourRobot[index].pos.loc)&&
+// // C2.contains(wm->ourRobot[index].pos.loc)&&
+// // (fabs(((wm->ourRobot[1].pos.loc-wm->ourRobot[index].pos.loc).dir().degree())-(vec2goal.dir().degree())<3))
+// // )
+// // {
+// // rc.kickspeedx=6;
+// // }
+
+
+
+
+
+
+
+// // ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////**
+
+// // //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////***
+
+// // // Vector2D A,A1,A2;
+
+// // // vec2goal.setLength(100);
+
+// // // A=wm->ball.pos.loc-vec2goal;
+
+// // // A1=A.rotatedVector(90);
+// // // A2=A.rotatedVector(-90);
+
+
+// // // qDebug()<<"A:"<ball.pos.loc,ROBOT_RADIUS+60000);
+// // // Circle2D C1(A1,300);
+// // // Circle2D C2(A2,300);
+
+// // // if( (C1.contains(wm->ourRobot[0].pos.loc)) && (C2.contains(wm->ourRobot[0].pos.loc)) )//(C.contains(wm->ourRobot[0].pos.loc))) )
+// // // {
+// // // rc.kickspeedx=10;
+// // // qDebug()<<"shoot";
+// // // }
+
+
+// // //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////***
+
+
+// //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+// // //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+// // /// //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+// // /// //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+// // /// /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+// //// //following ball...
+
+
+// //// if(wm->ball.isValid && wm->ball.vel.loc.length()>0.15 )//&& (wm->ourRobot[0].pos.loc-wm->ball.pos.loc).length()>115 )
+// //// {
+// //// double delta=0;
+// //// rc.maxSpeed=2.5;
+
+// //// Vector2D Ballpos=wm->ball.pos.loc;
+// //// Vector2D Ballvel=wm->ball.vel.loc;
+
+// //// Ballvel.setLength(130);
+// //// Vector2D A=Ballvel.rotatedVector(delta);
+
+// //// Vector2D goal=Ballpos+A;
+
+// //// if((wm->ourRobot[0].pos.loc-goal).length()<15)
+// //// {
+// //// rc.maxSpeed=wm->ball.vel.loc.length();
+// //// }
+
+// //// //qDebug()<<"V:"<ball.pos.loc-wm->ourRobot[0].pos.loc).dir().radian();
+
+// //// }
+
+// ////// qDebug()<<"ball angel:"<ball.pos.loc-wm->ourRobot[0].pos.loc;
+// //// rc.fin_pos.dir=robot2ball.dir().radian();
+
+// //// rc.fin_pos.loc={2470,0};
+
+
+// //// if (wm->ball.vel.loc.length()>0.1)
+// //// {
+// //// Vector2D goal;
+// //// Vector2D Ballpos=wm->ball.pos.loc;
+// //// Ball2C = new Line2D(Ballpos , wm->ball.vel.loc.dir().degree());
+// //// Vector2D A,B;
+
+// //// ballvel.setDir(wm->ball.vel.loc.dir().degree());
+
+
+// //// if(fabs(ballvel.dir().degree()-last_ballvel.dir().degree())>10)
+// //// {
+
+// //// C.assign(wm->ourRobot[0].pos.loc,ROBOT_RADIUS+300);
+
+// //// }
+
+// //// last_ballvel.setDir(ballvel.dir().degree());
+
+
+
+// //// C.intersection(*Ball2C,&A,&B);
+
+// //// if( C.HasIntersection(*Ball2C))
+// //// {
+// //// if((Ballpos-A).length2()>(Ballpos-B).length2())
+// //// {
+// //// goal=B;
+// //// }
+
+// //// else
+// //// {
+// //// goal=A;
+// //// }
+
+// //// rc.fin_pos.loc=goal;
+// //// rc.fin_pos.dir=(wm->ball.vel.loc.dir().radian()+M_PI);//tttarget.dir().radian();//
+
+
+// //// }
+
+
+
+// //// }
+// // /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+// // /////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+// // /// //////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+// // /// ////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
+// // ///
+// // ///
+
+// //// //sth like one touch...
+
+
+// ////// Vector2D vec2goal;
+
+// //// target={2480,2790};//wm->ourRobot[1].pos.loc;//
+
+// //// vec2goal=target-wm->ball.pos.loc;
+
+// //// vec2goal.setLength(95);
+
+
+
+
+
+
+
+
+
+
+// //// Vector2D robot2ball=wm->ball.pos.loc-wm->ourRobot[0].pos.loc;
+// //// rc.fin_pos.dir=robot2ball.dir().radian();
+
+// //// rc.fin_pos.loc={2470,0};
+
+// //// target={1500,0};
+
+
+// //// if (wm->ball.vel.loc.length()>0.1)
+// //// {
+// //// Vector2D goal;
+// //// Vector2D Ballpos=wm->ball.pos.loc;
+// //// Ball2C = new Line2D(Ballpos , wm->ball.vel.loc.dir().degree());
+// //// Vector2D A,B;
+
+// //// ballvel.setDir(wm->ball.vel.loc.dir().degree());
+
+
+// //// if(fabs(ballvel.dir().degree()-last_ballvel.dir().degree())>15)
+// //// {
+
+// //// C.assign(wm->ourRobot[0].pos.loc,ROBOT_RADIUS+200);
+
+// //// }
+
+// //// last_ballvel.setDir(ballvel.dir().degree());
+
+
+
+// //// C.intersection(*Ball2C,&A,&B);
+
+// //// if( C.HasIntersection(*Ball2C))
+// //// {
+// //// if((target-A).length2()>(target-B).length2())
+// //// {
+// //// goal=A;
+// //// }
+
+// //// else
+// //// {
+// //// goal=B;
+// //// }
+
+
+// //// rc.fin_pos.loc=goal - vec2goal;
+
+// //// rc.fin_pos.dir=vec2goal.dir().radian();
+
+
+// //// }
+
+
+
+// //// }
+
+
+
+//}
+
+
+
+
+void SkillKick::setTarget(const Vector2D &Target)
+{
+ _Target=Target;
+}
+
+void SkillKick::setKickType(bool isShoot)
+{
+ this->isShoot = isShoot;
+}
diff --git a/src/ai/skill/skillkick.h b/src/ai/skill/skillkick.h
old mode 100644
new mode 100755
diff --git a/src/ai/skill/skillonetouch.cpp b/src/ai/skill/skillonetouch.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/skill/skillonetouch.h b/src/ai/skill/skillonetouch.h
old mode 100644
new mode 100755
diff --git a/src/ai/skill/skillpassreceive.cpp b/src/ai/skill/skillpassreceive.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/skill/skillpassreceive.h b/src/ai/skill/skillpassreceive.h
old mode 100644
new mode 100755
diff --git a/src/ai/skill/skilltest.cpp b/src/ai/skill/skilltest.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/skill/skilltest.h b/src/ai/skill/skilltest.h
old mode 100644
new mode 100755
diff --git a/src/ai/soccer.cpp b/src/ai/soccer.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/soccer.h b/src/ai/soccer.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic.cpp b/src/ai/tactic.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic.h b/src/ai/tactic.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticattacker.cpp b/src/ai/tactic/tacticattacker.cpp
old mode 100644
new mode 100755
index 53f0e58..29490b9
--- a/src/ai/tactic/tacticattacker.cpp
+++ b/src/ai/tactic/tacticattacker.cpp
@@ -19,10 +19,12 @@ RobotCommand TacticAttacker::getCommand()
if(!wm->ourRobot[id].isValid) return rc;
rc.maxSpeed = 4;
+ AngleDeg degree=30+AngleDeg::PI;
+ // qDebug()<ourRobot[id].Status == AgentStatus::FollowingBall)
{
// tANDp target = findTarget();
-
Vector2D passSenderPos = wm->ourRobot[kickerID].pos.loc;
Vector2D OneTouchKickerPos = wm->ourRobot[this->id].pos.loc;
Vector2D passSender2OneTouchKicker = OneTouchKickerPos-passSenderPos;
@@ -68,7 +70,7 @@ RobotCommand TacticAttacker::getCommand()
}
rc.fin_pos = kickPos;
- rc.useNav = true;
+ rc.useNav = UseNav;
}
else
{
@@ -88,7 +90,7 @@ RobotCommand TacticAttacker::getCommand()
else if(wm->ourRobot[id].Status == AgentStatus::RecievingPass)
{
rc.fin_pos = idlePosition;
- rc.useNav = true;
+ rc.useNav = UseNav;
rc.isBallObs = true;
rc.isKickObs = true;
}
@@ -141,7 +143,7 @@ RobotCommand TacticAttacker::getCommand()
rc.fin_pos = final;
}
- rc.useNav = true;
+ rc.useNav = UseNav;
rc.isBallObs = true;
rc.isKickObs = true;
}
@@ -150,7 +152,7 @@ RobotCommand TacticAttacker::getCommand()
this->holdKickPos = false;
rc.fin_pos = idlePosition;
- rc.useNav = true;
+ rc.useNav = UseNav;
rc.isBallObs = true;
rc.isKickObs = true;
@@ -541,3 +543,9 @@ bool TacticAttacker::isFree(int index)
}
return true;
}
+bool TacticAttacker::getUseNav(){
+ return UseNav;
+}
+void TacticAttacker::setUseNav(bool input){
+ UseNav=input;
+}
diff --git a/src/ai/tactic/tacticattacker.h b/src/ai/tactic/tacticattacker.h
old mode 100644
new mode 100755
index 8d25c85..1b1502c
--- a/src/ai/tactic/tacticattacker.h
+++ b/src/ai/tactic/tacticattacker.h
@@ -38,7 +38,8 @@ class TacticAttacker : public Tactic
void setKickerID(int id);
bool everyOneInTheirPos;
-
+ void setUseNav(bool input);
+ bool getUseNav();
private:
bool isFree(int index);
@@ -55,7 +56,7 @@ class TacticAttacker : public Tactic
bool holdKickPos;
Position kickPos;
int kickerID;
-
+ bool UseNav=true;
protected:
bool canKick;
};
diff --git a/src/ai/tactic/tacticballtracker.cpp b/src/ai/tactic/tacticballtracker.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticballtracker.h b/src/ai/tactic/tacticballtracker.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticblocker.cpp b/src/ai/tactic/tacticblocker.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticblocker.h b/src/ai/tactic/tacticblocker.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticcircle.cpp b/src/ai/tactic/tacticcircle.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticcircle.h b/src/ai/tactic/tacticcircle.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticcontrol.cpp b/src/ai/tactic/tacticcontrol.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticcontrol.h b/src/ai/tactic/tacticcontrol.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticdefender.cpp b/src/ai/tactic/tacticdefender.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticdefender.h b/src/ai/tactic/tacticdefender.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticfixedpos.cpp b/src/ai/tactic/tacticfixedpos.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticfixedpos.h b/src/ai/tactic/tacticfixedpos.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticformation.cpp b/src/ai/tactic/tacticformation.cpp
old mode 100644
new mode 100755
index 3e43a72..d5d6ebd
--- a/src/ai/tactic/tacticformation.cpp
+++ b/src/ai/tactic/tacticformation.cpp
@@ -25,7 +25,7 @@ RobotCommand TacticFormation::getCommand()
{
qDebug()<<"append it";
if( this->leaderID == 0 )
- wm->debug_pos.append(wm->ourRobot[leaderID].pos.loc);
+ //wm->debug_pos.append(wm->ourRobot[leaderID].pos.loc);
path.append(wm->ourRobot[leaderID].pos);
}
diff --git a/src/ai/tactic/tacticformation.h b/src/ai/tactic/tacticformation.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticgoalie.cpp b/src/ai/tactic/tacticgoalie.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticgoalie.h b/src/ai/tactic/tacticgoalie.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tactichalt.cpp b/src/ai/tactic/tactichalt.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tactichalt.h b/src/ai/tactic/tactichalt.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tactickicklearning.cpp b/src/ai/tactic/tactickicklearning.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tactickicklearning.h b/src/ai/tactic/tactickicklearning.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticpenaltykicker.cpp b/src/ai/tactic/tacticpenaltykicker.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticpenaltykicker.h b/src/ai/tactic/tacticpenaltykicker.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticpreparing.cpp b/src/ai/tactic/tacticpreparing.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticpreparing.h b/src/ai/tactic/tacticpreparing.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticstop.cpp b/src/ai/tactic/tacticstop.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticstop.h b/src/ai/tactic/tacticstop.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tactictechnical.cpp b/src/ai/tactic/tactictechnical.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tactictechnical.h b/src/ai/tactic/tactictechnical.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tactictest.cpp b/src/ai/tactic/tactictest.cpp
old mode 100644
new mode 100755
index 1420b6f..8d37314
--- a/src/ai/tactic/tactictest.cpp
+++ b/src/ai/tactic/tactictest.cpp
@@ -1,17 +1,140 @@
#include "tactictest.h"
+#include
TacticTest::TacticTest(WorldModel *worldmodel, QObject *parent) :
Tactic("TacticTest", worldmodel, parent)
{
- sTest = new SkillKick(wm);
}
+
RobotCommand TacticTest::getCommand()
{
RobotCommand rc;
- if(!wm->ourRobot[id].isValid) return rc;
+<<<<<<< HEAD
+<<<<<<< HEAD
+ if(!wm->ourRobot[id].isValid)
+ return rc;
+ rc.fin_pos.loc.x = -3000;
+ rc.fin_pos.loc.y = 0;
+ rc.useNav = true;
+ rc.maxSpeed = 3;
+ qDebug() << wm->ourRobot[4].pos.loc.x <<" - " << wm->ourRobot[4].pos.loc.y;
+ return rc;
+// /*
+// * TAMARIN GHABL
- sTest->execute(rc);
+// rc0.maxSpeed = 3;
+// rc0.useNav = true;
+// rc1.maxSpeed = 3;
+// rc1.useNav = true;
+// if((id == 0)&&(firstPos1 == false)){
+// rc0.fin_pos.loc = Vector2D(-2000,1000);
+// firstPos1 = true;
+// }
+// else if((id == 1)&&(firstPos2 == false)){
+// rc1.fin_pos.loc = Vector2D(-2000,-1000);
+// firstPos2 = true;
+// }
+// else if((id == 0)&&(firstPos1 == true)&&(active == true)&&(firstPos2 == true)){
+// rc0.fin_pos.loc.x = wm->ourRobot[1].pos.loc.x;
+// if(std::abs(wm->ourRobot[0].pos.loc.x - wm->ourRobot[0].pos.loc.x) < 20){
+// active = false;
+// }
+// }
+// else if((id == 1)&&(firstPos2 == true)&&(active == false)&&(firstPos1 == true)){
+// rc1.fin_pos.loc = Vector2D(-wm->ourRobot[0].pos.loc.x,-1000);
+// if(std::abs(wm->ourRobot[1].pos.loc.x - (-wm->ourRobot[0].pos.loc.x)) < 20){
+// active = true;
+// }
+// }
+// if(id == 0)
+// return rc0;
+// if(id == 1)
+// return rc1;
- return rc;
-}
+// */
+// //Step1
+// qDebug() << "fskdfj";
+
+// if(!wm->ourRobot[id].isValid) return rc;
+//// // wm->debug_pos.clear();
+//// // wm->debug_pos.append(wm->ourRobot[1].pos.loc);
+//// // wm->debug_pos.append(wm->ourRobot[0].pos.loc);
+//// // Vector2D p2 = Field::ourGoalCenter;
+//// // Vector2D p1 = wm->ball.pos.loc;
+//// // Segment2D ballViewMidSeg(p2,p1);
+//// static double rad = 90;
+//// double khata = 0.2;
+//// if((id == 0) && (kicked == false)){
+//// Ray2D ray(wm->ourRobot[1].pos.loc,wm->ball.pos.loc);
+//// Circle2D cir(wm->ball.pos.loc,rad);
+//// Vector2D* v1 = new Vector2D();
+//// Vector2D* v2 = new Vector2D();
+//// cir.intersection(ray,v1,v2);
+//// if(v1->dist(wm->ourRobot[1].pos.loc) > v2->dist(wm->ourRobot[1].pos.loc)){
+//// rc.fin_pos.loc = *v1;
+//// rc.useNav = true;
+//// rc.maxSpeed = 3;
+//// Ray2D rayInvert(wm->ball.pos.loc,wm->ourRobot[1].pos.loc);
+//// rc.fin_pos.dir = rayInvert.dir().radian();
+//// rc.isBallObs = true;
+//// if(wm->ourRobot[0].pos.loc.dist(*v1) < 150){
+//// rc.maxSpeed = 3;
+//// rc.isBallObs = false;
+//// if(((std::abs(wm->ourRobot[0].pos.dir - rayInvert.dir().radian()) < khata) ||
+//// (((M_PI*2) - std::abs(wm->ourRobot[0].pos.dir - rayInvert.dir().radian())) < khata)) && (wm->ourRobot[0].pos.loc.dist(wm->ball.pos.loc) < 110)){
+//// rc.kickspeedx = 4;
+//// rc.kickspeedz = 1;
+//// kicked = true;
+//// }
+//// }
+//// }
+//// else{
+//// rc.fin_pos.loc = *v2;
+//// rc.useNav = true;
+//// rc.maxSpeed = 3;
+//// rc.isBallObs = true;
+//// if(wm->ourRobot[0].pos.loc.dist(*v2) < 150){
+//// rc.maxSpeed = 3;
+//// rc.isBallObs = false;
+//// Ray2D rayInvert(wm->ball.pos.loc,wm->ourRobot[1].pos.loc);
+//// rc.fin_pos.dir = rayInvert.dir().radian();
+//// double rand = ((double) std::rand() / (RAND_MAX));
+//// std::cout << (wm->ourRobot[0].pos.loc.dir() - rayInvert.dir()).radian() << std::endl;
+//// if(((std::abs(wm->ourRobot[0].pos.dir - rayInvert.dir().radian()) < khata) ||
+//// (((M_PI*2) - std::abs(wm->ourRobot[0].pos.dir - rayInvert.dir().radian())) < khata)) && (wm->ourRobot[0].pos.loc.dist(wm->ball.pos.loc) < 110)){
+//// rc.kickspeedx = 4;
+//// rc.kickspeedz = 1;
+//// kicked = true;
+//// }
+//// }
+//// }
+//// }
+//// if((id == 1) && (kicked == true)){
+//// AngleDeg angSefr(0);
+//// Line2D ray(wm->ourRobot[1].pos.loc,angSefr);
+//// Vector2D jabejaSorat(wm->ball.vel.loc.x - wm->ball.pos.loc.x,wm->ball.vel.loc.y - wm->ball.pos.loc.y);
+//// Line2D ray2(wm->ball.pos.loc,jabejaSorat);
+//// Vector2D javab = ray.intersection(ray2);
+//// rc.fin_pos.loc.x = javab.x;
+//// rc.fin_pos.loc.y = javab.y;
+//// rc.fin_pos.dir = (*(new Ray2D(wm->oppRobot[1].pos.loc,Field::ourGoalCenter))).dir().radian();
+//// rc.maxSpeed = 6;
+//// rc.useNav = true;
+//// if(wm->ourRobot[1].pos.loc.dist(wm->ball.pos.loc) < 700)
+//// kicked = false;
+//// }
+//// if((id == 1) && (kicked == false)){
+//// rc.fin_pos.loc.x = wm->ourRobot[1].pos.loc.x;
+//// rc.fin_pos.loc.y = wm->ourRobot[1].pos.loc.y;
+//// }
+//// if((id == 0) && (kicked == true)){
+//// rc.fin_pos.loc.x = wm->ourRobot[0].pos.loc.x;
+//// rc.fin_pos.loc.y = wm->ourRobot[0].pos.loc.y;
+//// }
+// rc.fin_pos.loc.x = -2800;
+// rc.fin_pos.loc.y = 0;
+// rc.useNav = true;
+// rc.maxSpeed = 2;
+// qDebug()<<"i am here";
+// return rc;
diff --git a/src/ai/tactic/tactictest.h b/src/ai/tactic/tactictest.h
old mode 100644
new mode 100755
index 3b2f8cb..6e02d3b
--- a/src/ai/tactic/tactictest.h
+++ b/src/ai/tactic/tactictest.h
@@ -4,14 +4,17 @@
#define DangerDist 300
class TacticTest : public Tactic
{
+private:
+ Vector2D* finalPos;
Q_OBJECT
public:
+ static bool kicked;
+ int flag=0;
+ int flag1=0;
+ int flag2=0;
+ int flag3=0;
explicit TacticTest(WorldModel *worldmodel, QObject *parent = 0);
virtual RobotCommand getCommand();
-
-private:
- Skill *sTest;
-
};
-#endif // TACTICTEST_H
+#endif //
diff --git a/src/ai/tactic/tactictest2.cpp b/src/ai/tactic/tactictest2.cpp
old mode 100644
new mode 100755
index 40fcffd..20a5e57
--- a/src/ai/tactic/tactictest2.cpp
+++ b/src/ai/tactic/tactictest2.cpp
@@ -1,12 +1,768 @@
#include "tactictest2.h"
+
+Vector2D* TacticTest2::getFinalPos()
+{
+ return &finalPos;
+}
+
+void TacticTest2::setFinalPos(Vector2D value)
+{
+ finalPos = value;
+}
+
+int TacticTest2::getBallVelocity() const
+{
+ return ballVelocity;
+}
+
+void TacticTest2::setBallVelocity(int value)
+{
+ ballVelocity = value;
+}
TacticTest2::TacticTest2(WorldModel *worldmodel, QObject *parent) :
Tactic("TacticTest2", worldmodel, parent)
{
}
+
RobotCommand TacticTest2::getCommand()
{
RobotCommand rc;
if(!wm->ourRobot[id].isValid) return rc;
+ Vector2D p2 = Field::ourGoalCenter;
+ Vector2D p1 = wm->ball.pos.loc;
+ Segment2D ballViewMidSeg(p2,p1);
+ //goal keeper
+ if(id == wm->ref_goalie_our){
+ if(wm->ball.vel.loc.r() < 0.1){
+ rc.fin_pos.loc = Field::ourGoalCenter;
+ rc.fin_pos.dir = ballViewMidSeg.direction().radian();
+ rc.maxSpeed = 2;
+ return rc;
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 3;
+ Ray2D seg(wm->ball.pos.loc,wm->ball.vel.loc.dir());
+ rc.fin_pos.loc = seg.intersection(Field::leftLine);
+ // rc.fin_pos.dir = seg.direction().deg2rad(seg.direction().degree());
+ if((rc.fin_pos.loc.y < Field::ourGoalPost_L.y+5) && (rc.fin_pos.loc.y > Field::ourGoalPost_R.y-5) && (rc.fin_pos.loc.x = Field::ourGoalPost_L.x))
+ return rc;
+ else
+ rc.fin_pos.loc = Field::ourGoalCenter;
+ rc.maxSpeed = 2;
+ return rc;
+ }
+ double ang = 7;
+ AngleDeg zaveEkhtelaf(30);
+// Vector2D p2 = Field::ourGoalPost_L;
+// Vector2D p3 = Field::ourGoalPost_R;
+
+ /*
+ Segment2D SegBallView1(wm->ball.pos.loc,Field::ourDefPost_R);
+ Segment2D SegBallView2(wm->ball.pos.loc,Field::ourDefPost_L);*/
+// ballViewMidSeg.direction().;
+/* Segment2D ballViewBotLine(p1,p3);
+ Segment2D ballViewTopLine(p1,p2)*/;
+ if(id == wm->kn->ActiveAgents()[1]){
+ Segment2D* seg;
+ if(wm->ball.vel.loc.r() > 0.1){
+ seg = new Segment2D(p2,Field::goalCircle_R + 200,*(new AngleDeg(ballViewMidSeg.direction().degree() + 1)));
+ rc.useNav = true;
+ rc.maxSpeed = 6;
+
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 200,*(new AngleDeg(ballViewMidSeg.direction().degree() + ang)));
+ rc.useNav = true;
+ rc.maxSpeed = 4;
+ }
+ rc.fin_pos.loc = seg->terminal();
+ rc.fin_pos.dir = seg->direction().radian();
+ rc.maxSpeed = 4;
+ }
+ if(id == wm->kn->ActiveAgents()[2]){
+ Segment2D* seg;
+ if(wm->ball.vel.loc.r() > 0.1){
+ seg = new Segment2D(p2,Field::goalCircle_R + 200,*(new AngleDeg(ballViewMidSeg.direction().degree() - 1)));
+ rc.useNav = true;
+ rc.maxSpeed = 6;
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 200,*(new AngleDeg(ballViewMidSeg.direction().degree()- ang)));
+ rc.useNav = true;
+ rc.maxSpeed = 4;
+ }
+ rc.fin_pos.loc = seg->terminal();
+ rc.fin_pos.dir = seg->direction().radian();
+ }
+ if(wm->kn->ActiveAgents().size() > 3){
+ if(id == wm->kn->ActiveAgents()[3]){
+ Segment2D* seg;
+ if(wm->ball.vel.loc.r() > 0.1){
+ Segment2D seg2(p2,wm->ball.pos.loc);
+ if(seg2.length() > Field::goalCircle_R + 300){
+ seg = new Segment2D(p2,seg2.length() - 500,*(new AngleDeg(ballViewMidSeg.direction().degree())));
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 300,*(new AngleDeg(ballViewMidSeg.direction().degree())));
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 6;
+
+ }
+ else{
+ Segment2D seg2(p2,wm->ball.pos.loc);
+ if(seg2.length() > Field::goalCircle_R + 300){
+ seg = new Segment2D(p2,seg2.length() - 500,*(new AngleDeg(ballViewMidSeg.direction().degree())));
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 300,*(new AngleDeg(ballViewMidSeg.direction().degree())));
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 4;
+ }
+ rc.fin_pos.loc = seg->terminal();
+ rc.fin_pos.dir = seg->direction().radian();
+ rc.maxSpeed = 4;
+ }
+ }
+ if(wm->kn->ActiveAgents().size() == 5){
+ if(id == wm->kn->ActiveAgents()[4]){
+ Segment2D* seg;
+ if(wm->ball.vel.loc.r() > 0.1){
+ Segment2D seg2(p2,wm->ball.pos.loc);
+ if(seg2.length() > Field::goalCircle_R + 500){
+ Segment2D seg5(wm->ball.pos.loc,p2);
+ Segment2D seg4(wm->ball.pos.loc , 500 , seg5.direction() - zaveEkhtelaf);
+ rc.fin_pos.loc = seg4.terminal();
+ Segment2D seg3(seg4.terminal(),wm->ball.pos.loc);
+ rc.fin_pos.dir = seg3.direction().radian();
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 300,*(new AngleDeg(ballViewMidSeg.direction().degree() - 2*ang)));
+ rc.fin_pos.loc = seg->terminal();
+ rc.fin_pos.dir = seg->direction().radian();
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 6;
+
+ }
+ else{
+ Segment2D seg2(p2,wm->ball.pos.loc);
+ if(seg2.length() > Field::goalCircle_R + 500){
+ Segment2D seg5(wm->ball.pos.loc,p2);
+ Segment2D seg4(wm->ball.pos.loc , 500 , seg5.direction() - zaveEkhtelaf);
+ rc.fin_pos.loc = seg4.terminal();
+ Segment2D seg3(seg4.terminal(),wm->ball.pos.loc);
+ rc.fin_pos.dir = seg3.direction().radian();
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 300,*(new AngleDeg(ballViewMidSeg.direction().degree() - 2*ang)));
+ rc.fin_pos.loc = seg->terminal();
+ rc.fin_pos.dir = seg->direction().radian();
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 4;
+ }
+ rc.maxSpeed = 4;
+ }
+ }
+ if(wm->kn->ActiveAgents().size() == 6){
+ Vector2D* j1 = new Vector2D();
+ Vector2D* j2 = new Vector2D();
+ if((id == wm->kn->ActiveAgents()[4]) || (id == wm->kn->ActiveAgents()[5])){
+ Segment2D* seg;
+ if(wm->ball.vel.loc.r() > 0.1){
+ Segment2D seg2(p2,wm->ball.pos.loc);
+ if(seg2.length() > Field::goalCircle_R + 500){
+ Segment2D seg5(wm->ball.pos.loc,p2);
+ Segment2D seg4(wm->ball.pos.loc , 500 , seg5.direction() - zaveEkhtelaf);
+ rc.fin_pos.loc = seg4.terminal();
+ Segment2D seg3(seg4.terminal(),wm->ball.pos.loc);
+ rc.fin_pos.dir = seg3.direction().radian();
+ /*
+ Circle2D cir1(p2,Field::goalCircle_R + 600 + (((seg2.length() - Field::goalCircle_R - 500)/3)*2));
+ Circle2D cir2(wm->ball.pos.loc,200 + ((seg2.length() - Field::goalCircle_R - 500)/3));
+ cir1.intersection(cir2,j1,j2);
+ std::cout << "j21 x" << j2->x << std::endl;
+ rc.fin_pos.loc = *j1;
+ Segment2D seg3(*j1,wm->ball.pos.loc);
+ rc.fin_pos.dir = seg3.direction().radian();*/
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 300,*(new AngleDeg(ballViewMidSeg.direction().degree() + 2*ang)));
+ rc.fin_pos.loc = seg->terminal();
+ rc.fin_pos.dir = seg->direction().radian();
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 6;
+
+ }
+ else{
+ Segment2D seg2(p2,wm->ball.pos.loc);
+ if(seg2.length() > Field::goalCircle_R + 500){
+ Segment2D seg5(wm->ball.pos.loc,p2);
+ Segment2D seg4(wm->ball.pos.loc , 500 , seg5.direction() - zaveEkhtelaf);
+ rc.fin_pos.loc = seg4.terminal();
+ Segment2D seg3(seg4.terminal(),wm->ball.pos.loc);
+ rc.fin_pos.dir = seg3.direction().radian();
+ /*
+ Circle2D cir1(p2,Field::goalCircle_R + 600 + (((seg2.length() - Field::goalCircle_R - 500)/3)*2));
+ Circle2D cir2(wm->ball.pos.loc,200 + ((seg2.length() - Field::goalCircle_R - 500)/3));
+ cir1.intersection(cir2,j1,j2);
+ std::cout << "j22 x" << j2->x << std::endl;
+ rc.fin_pos.loc = *j1;
+ Segment2D seg3(*j1,wm->ball.pos.loc);
+ rc.fin_pos.dir = seg3.direction().radian();*/
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 300,*(new AngleDeg(ballViewMidSeg.direction().degree() + 2*ang)));
+ rc.fin_pos.loc = seg->terminal();
+ rc.fin_pos.dir = seg->direction().radian();
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 4;
+ }
+ rc.maxSpeed = 4;
+ }
+ if(id == wm->kn->ActiveAgents()[5]){
+ Segment2D* seg;
+ if(wm->ball.vel.loc.r() > 0.1){
+ Segment2D seg2(p2,wm->ball.pos.loc);
+ if(seg2.length() > Field::goalCircle_R + 500){
+ Segment2D seg5(wm->ball.pos.loc,p2);
+ Segment2D seg4(wm->ball.pos.loc , 500 , seg5.direction() + zaveEkhtelaf);
+ rc.fin_pos.loc = seg4.terminal();
+ Segment2D seg3(seg4.terminal(),wm->ball.pos.loc);
+ rc.fin_pos.dir = seg3.direction().radian();
+ // std::cout << "x : " << j2->x << std::endl;
+// std::cout << "y : " << j2->y << std::endl;
+// rc.fin_pos.loc = *j2;
+// std::cout << "1x : " << j2->x << std::endl;
+// std::cout << "1y : " << j2->y << std::endl;
+//// std::cout << "fasele do dayere" << cir1.center().dist(cir2.center()) << " jame shoaha" << (cir1.radius() + cir2.radius()) << std::endl;
+// Segment2D seg3(*j2,wm->ball.pos.loc);
+// rc.fin_pos.dir = seg3.direction().radian();
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 300,*(new AngleDeg(ballViewMidSeg.direction().degree() - 2*ang)));
+ rc.fin_pos.loc = seg->terminal();
+ rc.fin_pos.dir = seg->direction().radian();
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 6;
+
+ }
+ else{
+ Segment2D seg2(p2,wm->ball.pos.loc);
+ if(seg2.length() > Field::goalCircle_R + 500){
+ Segment2D seg5(wm->ball.pos.loc,p2);
+ Segment2D seg4(wm->ball.pos.loc , 500 , seg5.direction() + zaveEkhtelaf);
+ rc.fin_pos.loc = seg4.terminal();
+ Segment2D seg3(seg4.terminal(),wm->ball.pos.loc);
+ rc.fin_pos.dir = seg3.direction().radian();
+ // std::cout << "2x : " << j2->x << std::endl;
+// std::cout << "2y : " << j2->y << std::endl;
+//// std::cout << "fasele do dayere" << cir1.center().dist(cir2.center()) << " jame shoaha" << (cir1.radius() + cir2.radius()) << std::endl;
+// rc.fin_pos.loc = *j2;
+// Segment2D seg3(*j2,wm->ball.pos.loc);
+// rc.fin_pos.dir = seg3.direction().radian();
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 300,*(new AngleDeg(ballViewMidSeg.direction().degree() - 2*ang)));
+ rc.fin_pos.loc = seg->terminal();
+ rc.fin_pos.dir = seg->direction().radian();
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 4;
+ }
+ rc.maxSpeed = 4;
+ }
+ }
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ qDebug() << ballViewMidSeg.direction().radian();
+ if((ballViewMidSeg.direction().radian() > 1.1)&& (id == 4) && (wm->kn->ActiveAgents().size() == 6)){
+ Segment2D* seg;
+ if(wm->ball.vel.loc.r() > 0.1){
+ Segment2D seg2(p2,wm->ball.pos.loc);
+ if(seg2.length() > Field::goalCircle_R + 500){
+ Segment2D seg5(wm->ball.pos.loc,p2);
+ Segment2D seg4(wm->ball.pos.loc , 500 , seg5.direction() + zaveEkhtelaf + zaveEkhtelaf);
+ rc.fin_pos.loc = seg4.terminal();
+ Segment2D seg3(seg4.terminal(),wm->ball.pos.loc);
+ rc.fin_pos.dir = seg3.direction().radian();
+ // std::cout << "x : " << j2->x << std::endl;
+// std::cout << "y : " << j2->y << std::endl;
+// rc.fin_pos.loc = *j2;
+// std::cout << "1x : " << j2->x << std::endl;
+// std::cout << "1y : " << j2->y << std::endl;
+//// std::cout << "fasele do dayere" << cir1.center().dist(cir2.center()) << " jame shoaha" << (cir1.radius() + cir2.radius()) << std::endl;
+// Segment2D seg3(*j2,wm->ball.pos.loc);
+// rc.fin_pos.dir = seg3.direction().radian();
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 300,*(new AngleDeg(ballViewMidSeg.direction().degree() + 2*ang)));
+ rc.fin_pos.loc = seg->terminal();
+ rc.fin_pos.dir = seg->direction().radian();
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 6;
+
+ }
+ else{
+ Segment2D seg2(p2,wm->ball.pos.loc);
+ if(seg2.length() > Field::goalCircle_R + 500){
+ Segment2D seg5(wm->ball.pos.loc,p2);
+ Segment2D seg4(wm->ball.pos.loc , 500 , seg5.direction() + zaveEkhtelaf + zaveEkhtelaf);
+ rc.fin_pos.loc = seg4.terminal();
+ Segment2D seg3(seg4.terminal(),wm->ball.pos.loc);
+ rc.fin_pos.dir = seg3.direction().radian();
+ // std::cout << "2x : " << j2->x << std::endl;
+// std::cout << "2y : " << j2->y << std::endl;
+//// std::cout << "fasele do dayere" << cir1.center().dist(cir2.center()) << " jame shoaha" << (cir1.radius() + cir2.radius()) << std::endl;
+// rc.fin_pos.loc = *j2;
+// Segment2D seg3(*j2,wm->ball.pos.loc);
+// rc.fin_pos.dir = seg3.direction().radian();
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 300,*(new AngleDeg(ballViewMidSeg.direction().degree() + 2*ang)));
+ rc.fin_pos.loc = seg->terminal();
+ rc.fin_pos.dir = seg->direction().radian();
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 4;
+ }
+ rc.maxSpeed = 4;
+ }
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ if((ballViewMidSeg.direction().radian() < -1.1)&& (id == 5) && (wm->kn->ActiveAgents().size() == 6)){
+ Segment2D* seg;
+ if(wm->ball.vel.loc.r() > 0.1){
+ Segment2D seg2(p2,wm->ball.pos.loc);
+ if(seg2.length() > Field::goalCircle_R + 500){
+ Segment2D seg5(wm->ball.pos.loc,p2);
+ Segment2D seg4(wm->ball.pos.loc , 500 , seg5.direction() - zaveEkhtelaf - zaveEkhtelaf);
+ rc.fin_pos.loc = seg4.terminal();
+ Segment2D seg3(seg4.terminal(),wm->ball.pos.loc);
+ rc.fin_pos.dir = seg3.direction().radian();
+ // std::cout << "x : " << j2->x << std::endl;
+// std::cout << "y : " << j2->y << std::endl;
+// rc.fin_pos.loc = *j2;
+// std::cout << "1x : " << j2->x << std::endl;
+// std::cout << "1y : " << j2->y << std::endl;
+//// std::cout << "fasele do dayere" << cir1.center().dist(cir2.center()) << " jame shoaha" << (cir1.radius() + cir2.radius()) << std::endl;
+// Segment2D seg3(*j2,wm->ball.pos.loc);
+// rc.fin_pos.dir = seg3.direction().radian();
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 300,*(new AngleDeg(ballViewMidSeg.direction().degree() - 2*ang)));
+ rc.fin_pos.loc = seg->terminal();
+ rc.fin_pos.dir = seg->direction().radian();
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 6;
+
+ }
+ else{
+ Segment2D seg2(p2,wm->ball.pos.loc);
+ if(seg2.length() > Field::goalCircle_R + 500){
+ Segment2D seg5(wm->ball.pos.loc,p2);
+ Segment2D seg4(wm->ball.pos.loc , 500 , seg5.direction() - zaveEkhtelaf - zaveEkhtelaf);
+ rc.fin_pos.loc = seg4.terminal();
+ Segment2D seg3(seg4.terminal(),wm->ball.pos.loc);
+ rc.fin_pos.dir = seg3.direction().radian();
+ // std::cout << "2x : " << j2->x << std::endl;
+// std::cout << "2y : " << j2->y << std::endl;
+//// std::cout << "fasele do dayere" << cir1.center().dist(cir2.center()) << " jame shoaha" << (cir1.radius() + cir2.radius()) << std::endl;
+// rc.fin_pos.loc = *j2;
+// Segment2D seg3(*j2,wm->ball.pos.loc);
+// rc.fin_pos.dir = seg3.direction().radian();
+ }
+ else{
+ seg = new Segment2D(p2,Field::goalCircle_R + 300,*(new AngleDeg(ballViewMidSeg.direction().degree() - 2*ang)));
+ rc.fin_pos.loc = seg->terminal();
+ rc.fin_pos.dir = seg->direction().radian();
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 4;
+ }
+ rc.maxSpeed = 4;
+ }
+// Vector2D* p4;
+// Segment2D* S1;
+// if(ballViewBotLine.length() < ballViewTopLine.length()){
+// AngleDeg A1(ballViewMidSeg.direction().degree() + 90);
+// Line2D l1(p3,A1);
+// p4 = &ballViewBotLine.intersection(l1);
+// S1 = new Segment2D(p3,&p4);
+// int ScaleNum = (S1->length()/(2*robotSize));
+// AngleDeg A2(-ballViewBotLine.direction().degree());
+// Segment2D MainTriBot(p1,ScaleNum*ballViewBotLine,A2);
+
+<<<<<<< HEAD
+// }
+// else{
+// AngleDeg A1(ballViewMidSeg.direction().degree() + 90);
+// Line2D l1(p2,A1);
+// p4 = &ballViewBotLine.intersection(l1);
+// S1 = new Segment2D(p2,&p4);
+// int ScaleNum = (S1->length()/(2*robotSize));
+// AngleDeg A2(-ballViewTopLine.direction().degree());
+// Segment2D MainTriTop(p1,ScaleNum*ballViewBotLine,A2);
+// }
+=======
+ if(id==5){ //3
+ Circle2D ballArea(wm->ball.pos.loc,300);
+ Circle2D ballShoutArea(wm->ball.pos.loc,ROBOT_RADIUS-40);
+ //Line2D shutLine(wm->ball.pos.loc,Field::ourGoalCenter);
+ Line2D shutLine(wm->ball.pos.loc,Field::ourGoalCenter);
+ Vector2D f1,f2,r;
+ Vector2D s1,s2,rf;
+ ballArea.intersection(shutLine,&f1,&f2);
+ if(Field::ourGoalCenter.dist(f1)>Field::ourGoalCenter.dist(f2)){
+ r=f1;
+ }
+ else{
+ r=f2;
+ }
+ if(r.dist(wm->ourRobot[id].pos.loc)>200 && flag==0){
+ rc.fin_pos.loc=r;
+ wm->debug_pos.append(r);
+ rc.maxSpeed=2;
+ rc.useNav=true;
+ rc.isBallObs=true;
+ qDebug()<<"ba navigatione roshan mire poshtesh";
+// //flag1=0;
+
+ }
+ else{
+ qDebug()<<"reside poshtesh";
+ rc.fin_pos.loc=r;
+ rc.maxSpeed=1;
+ rc.useNav=true;
+ rc.isBallObs=true;
+ //if(((wm->ourRobot[id].pos.dir)-(wm->ball.pos.loc-Field::ourGoalCenter).dir().radian())<0.9){
+ qDebug()<<"zavie ro ok karde flag ro 1 mikone ";
+ flag=1;
+ //}
+ }
+ ballShoutArea.intersection(shutLine,&s1,&s2);
+ if(Field::ourGoalCenter.dist(s1)>Field::ourGoalCenter.dist(s2)){
+ rf=s1;
+ }
+ else{
+ rf=s2;
+ }
+ if(flag==1){
+ qDebug()<<"ba sorate yek az posht be tup nazdik mishe";
+ rc.maxSpeed=0.5;
+//// if(wm->ourRobot[id].pos.loc.dist(wm->ball.pos.loc)>400){
+//// flag=0;
+//// }
+ rc.fin_pos.loc=rf;
+ wm->debug_pos.append(rf);
+ rc.useNav=false;
+ }
+ if(wm->ourRobot[id].pos.loc.dist(rf)ball.isValid && ((wm->ourRobot[id].pos.dir)-(wm->ball.pos.loc-Field::ourGoalCenter).dir().radian())<1){
+ qDebug()<<"dasture shut !";
+ rc.kickspeedx=100;
+ //}
+ rc.useNav=false;
+ //rc.isBallObs=false;
+ //rc.isKickObs=true;
+// flag=0;
+
+ }
+ rc.fin_pos.dir=(Field::ourGoalCenter-wm->ball.pos.loc).dir().radian();
+ }
+ if(id==4){
+ //way.append(wm->ball.pos.dir);
+ Position goaliePos;
+ if(wm->ball.vel.loc.length()<0.3){
+ int kickerId;
+ QList opp = wm->kn->findNearestTo(wm->ball.pos.loc);
+ for(int i=0;iball.pos.loc,wm->ourRobot[kickerId].pos.loc);
+ Segment2D gLine(Field::ourGoalPost_L,Field::ourGoalPost_R);
+ goaliePos.loc=gLine.intersection(shot);
+ if(gLine.contains(goaliePos.loc)==false){
+ goaliePos.loc=Field::ourGoalCenter;
+ }
+ goaliePos.dir=(wm->ball.pos.loc-goaliePos.loc).dir().radian();
+ }
+ else{
+ goaliePos.loc=Field::ourGoalCenter;
+ }
+ //
+ }
+ else{
+ qDebug()<<"else !!!!!";
+ Vector2D f;
+ Vector2D a;
+ Vector2D sum;
+ Vector2D avg;
+ sum.x=0;
+ sum.y=0;
+ f.x=wm->ball.pos.loc.x+wm->ball.vel.loc.x;
+ f.y=wm->ball.pos.loc.y+wm->ball.vel.loc.y;
+
+ //avg.x=way.at(0).x+way.at(1).x+way.at(2).x;
+ //avg.y=way.at(0).y+way.at(1).y+way.at(2).y;
+ Line2D shot(wm->ball.pos.loc,f);
+ Vector2D GL,GR;
+ GL=Field::ourGoalPost_L;
+ GR=Field::ourGoalPost_R;
+ if(Field::ourGoalPost_L.y>0){
+ GL.y+=100;
+ }
+ else{
+ GL.y-=100;
+ }
+ if(Field::ourGoalPost_R.y>0){
+ GR.y+=100;
+ }
+ else{
+ GR.y-=100;
+ }
+ Segment2D gLine(GL,GR);
+ a=gLine.intersection(shot);
+ if(gLine.contains(a)){
+ goaliePos.loc=a;
+ }
+ else{
+ goaliePos.loc=Field::ourGoalCenter;
+ }
+// if(goaliePos.loc.dist(Field::ourGoalCenter)<150){
+ if(wm->ball.pos.loc.dist(Field::ourGoalCenter)>450){
+ if(wm->ourRobot[id].pos.loc.dist(goaliePos.loc)>100){
+ if(goaliePos.loc.y>Field::ourGoalCenter.y){
+ goaliePos.loc.y+=50;
+ }
+ if(goaliePos.loc.yball.pos.loc-goaliePos.loc).dir().radian();
+ rc.fin_pos.loc=goaliePos.loc;
+ rc.fin_pos.dir=goaliePos.dir;
+ wm->debug_pos.append(goaliePos.loc);
+ rc.useNav=false;
+ rc.maxSpeed=4;
+ }
+
+<<<<<<< HEAD
+ //wm->debug_pos.append(Field::ourGoalCenter);
+ //wm->debug_pos.append(Field::ourGoalPost_L);
+ //wm->debug_pos.append(Field::ourGoalPost_R);
+>>>>>>> d766c95da96dc8ee70e0992aefe4e0a62d783e28
+=======
+ if(id==5){ //3
+ Circle2D ballArea(wm->ball.pos.loc,300);
+ Circle2D ballShoutArea(wm->ball.pos.loc,ROBOT_RADIUS-40);
+ //Line2D shutLine(wm->ball.pos.loc,Field::ourGoalCenter);
+ Line2D shutLine(wm->ball.pos.loc,Field::ourGoalCenter);
+ Vector2D f1,f2,r;
+ Vector2D s1,s2,rf;
+ ballArea.intersection(shutLine,&f1,&f2);
+ if(Field::ourGoalCenter.dist(f1)>Field::ourGoalCenter.dist(f2)){
+ r=f1;
+ }
+ else{
+ r=f2;
+ }
+ if(r.dist(wm->ourRobot[id].pos.loc)>200 && flag==0){
+ rc.fin_pos.loc=r;
+ wm->debug_pos.append(r);
+ rc.maxSpeed=2;
+ rc.useNav=true;
+ rc.isBallObs=true;
+ qDebug()<<"ba navigatione roshan mire poshtesh";
+// //flag1=0;
+
+ }
+ else{
+ qDebug()<<"reside poshtesh";
+ rc.fin_pos.loc=r;
+ rc.maxSpeed=1;
+ rc.useNav=true;
+ rc.isBallObs=true;
+ //if(((wm->ourRobot[id].pos.dir)-(wm->ball.pos.loc-Field::ourGoalCenter).dir().radian())<0.9){
+ qDebug()<<"zavie ro ok karde flag ro 1 mikone ";
+ flag=1;
+ //}
+ }
+ ballShoutArea.intersection(shutLine,&s1,&s2);
+ if(Field::ourGoalCenter.dist(s1)>Field::ourGoalCenter.dist(s2)){
+ rf=s1;
+ }
+ else{
+ rf=s2;
+ }
+ if(flag==1){
+ qDebug()<<"ba sorate yek az posht be tup nazdik mishe";
+ rc.maxSpeed=0.5;
+//// if(wm->ourRobot[id].pos.loc.dist(wm->ball.pos.loc)>400){
+//// flag=0;
+//// }
+ rc.fin_pos.loc=rf;
+ wm->debug_pos.append(rf);
+ rc.useNav=false;
+ }
+ if(wm->ourRobot[id].pos.loc.dist(rf)ball.isValid && ((wm->ourRobot[id].pos.dir)-(wm->ball.pos.loc-Field::ourGoalCenter).dir().radian())<1){
+ qDebug()<<"dasture shut !";
+ rc.kickspeedx=100;
+ //}
+ rc.useNav=false;
+ //rc.isBallObs=false;
+ //rc.isKickObs=true;
+// flag=0;
+
+ }
+ rc.fin_pos.dir=(Field::ourGoalCenter-wm->ball.pos.loc).dir().radian();
+ }
+ if(id==4){
+ //way.append(wm->ball.pos.dir);
+ Position goaliePos;
+ if(wm->ball.vel.loc.length()<0.3){
+ int kickerId;
+ QList opp = wm->kn->findNearestTo(wm->ball.pos.loc);
+ for(int i=0;iball.pos.loc,wm->ourRobot[kickerId].pos.loc);
+ Segment2D gLine(Field::ourGoalPost_L,Field::ourGoalPost_R);
+ goaliePos.loc=gLine.intersection(shot);
+ if(gLine.contains(goaliePos.loc)==false){
+ goaliePos.loc=Field::ourGoalCenter;
+ }
+ goaliePos.dir=(wm->ball.pos.loc-goaliePos.loc).dir().radian();
+ }
+ else{
+ goaliePos.loc=Field::ourGoalCenter;
+ }
+ //
+ }
+ else{
+ qDebug()<<"else !!!!!";
+ Vector2D f;
+ Vector2D a;
+ Vector2D sum;
+ Vector2D avg;
+ sum.x=0;
+ sum.y=0;
+ f.x=wm->ball.pos.loc.x+wm->ball.vel.loc.x;
+ f.y=wm->ball.pos.loc.y+wm->ball.vel.loc.y;
+
+ //avg.x=way.at(0).x+way.at(1).x+way.at(2).x;
+ //avg.y=way.at(0).y+way.at(1).y+way.at(2).y;
+ Line2D shot(wm->ball.pos.loc,f);
+ Vector2D GL,GR;
+ GL=Field::ourGoalPost_L;
+ GR=Field::ourGoalPost_R;
+ if(Field::ourGoalPost_L.y>0){
+ GL.y+=100;
+ }
+ else{
+ GL.y-=100;
+ }
+ if(Field::ourGoalPost_R.y>0){
+ GR.y+=100;
+ }
+ else{
+ GR.y-=100;
+ }
+ Segment2D gLine(GL,GR);
+ a=gLine.intersection(shot);
+ if(gLine.contains(a)){
+ goaliePos.loc=a;
+ }
+ else{
+ goaliePos.loc=Field::ourGoalCenter;
+ }
+// if(goaliePos.loc.dist(Field::ourGoalCenter)<150){
+ if(wm->ball.pos.loc.dist(Field::ourGoalCenter)>450){
+ if(wm->ourRobot[id].pos.loc.dist(goaliePos.loc)>100){
+ if(goaliePos.loc.y>Field::ourGoalCenter.y){
+ goaliePos.loc.y+=50;
+ }
+ if(goaliePos.loc.yball.pos.loc-goaliePos.loc).dir().radian();
+ rc.fin_pos.loc=goaliePos.loc;
+ rc.fin_pos.dir=goaliePos.dir;
+ wm->debug_pos.append(goaliePos.loc);
+ rc.useNav=false;
+ rc.maxSpeed=4;
+ }
+ //wm->debug_pos.append(Field::ourGoalCenter);
+ //wm->debug_pos.append(Field::ourGoalPost_L);
+ //wm->debug_pos.append(Field::ourGoalPost_R);
+ rc.fin_pos.loc = Vector2D(1300,100);
+ rc.maxSpeed = 2;
+ rc.useNav = true;
+>>>>>>> 4bde963eede2897a0748e0221474ee6c1450efde
return rc;
+ //baraye rahati dayere tarif mikonim.
}
diff --git a/src/ai/tactic/tactictest2.h b/src/ai/tactic/tactictest2.h
old mode 100644
new mode 100755
index a60e6b9..858d7f2
--- a/src/ai/tactic/tactictest2.h
+++ b/src/ai/tactic/tactictest2.h
@@ -6,10 +6,27 @@
class TacticTest2: public Tactic
{
+private:
+ Vector2D finalPos;
+ int ballVelocity;
Q_OBJECT
public:
+ int flag=0;
+ int flag1=0;
+ QList way;
explicit TacticTest2(WorldModel *worldmodel, QObject *parent = 0);
virtual RobotCommand getCommand();
+<<<<<<< HEAD
+<<<<<<< HEAD
+ Vector2D* getFinalPos();
+ void setFinalPos(Vector2D value);
+ int getBallVelocity() const;
+ void setBallVelocity(int value);
+=======
+>>>>>>> d766c95da96dc8ee70e0992aefe4e0a62d783e28
+=======
+private:
+>>>>>>> 4bde963eede2897a0748e0221474ee6c1450efde
};
#endif // TACTICTEST2_H
diff --git a/src/ai/tactic/tactictestfriction.cpp b/src/ai/tactic/tactictestfriction.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tactictestfriction.h b/src/ai/tactic/tactictestfriction.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tactictestkickprecision.cpp b/src/ai/tactic/tactictestkickprecision.cpp
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tactictestkickprecision.h b/src/ai/tactic/tactictestkickprecision.h
old mode 100644
new mode 100755
diff --git a/src/ai/tactic/tacticteststandingforwardenemy.cpp b/src/ai/tactic/tacticteststandingforwardenemy.cpp
new file mode 100755
index 0000000..eb78de2
--- /dev/null
+++ b/src/ai/tactic/tacticteststandingforwardenemy.cpp
@@ -0,0 +1,48 @@
+#include "tacticteststandingforwardenemy.h"
+
+
+int TacticTestStandingForwardEnemy::getDistance() const
+{
+ return distance;
+}
+
+void TacticTestStandingForwardEnemy::setDistance(int value)
+{
+ distance = value;
+}
+
+int TacticTestStandingForwardEnemy::getOppRobotIndex() const
+{
+ return OppRobotIndex;
+}
+
+void TacticTestStandingForwardEnemy::setOppRobotIndex(int value)
+{
+ OppRobotIndex = value;
+}
+TacticTestStandingForwardEnemy::TacticTestStandingForwardEnemy(WorldModel *worldmodel, QObject *parent) :
+ Tactic("TacticTest", worldmodel, parent)
+{
+}
+
+RobotCommand TacticTestStandingForwardEnemy::getCommand(){
+ RobotCommand rc;
+ if(!wm->ourRobot[id].isValid)
+ return rc;
+ rcsc::Segment2D line(wm->oppRobot[OppRobotIndex].pos.loc,Field::ourGoalCenter);
+ rcsc::Circle2D circle(wm->oppRobot[OppRobotIndex].pos.loc,distance);
+ Vector2D* v1 = new Vector2D();
+ Vector2D* v2 = new Vector2D();
+ circle.intersection(line,v1,v2);
+ if((v1->x != 0) && (v1->y != 0)){
+ rc.fin_pos.loc.x = v1->x;
+ rc.fin_pos.loc.y = v1->y;
+ }
+ if((v2->x != 0) && (v2->y != 0)){
+ rc.fin_pos.loc.x = v2->x;
+ rc.fin_pos.loc.y = v2->y;
+ }
+ rc.useNav = true;
+ rc.maxSpeed = 3;
+ return rc;
+}
diff --git a/src/ai/tactic/tacticteststandingforwardenemy.h b/src/ai/tactic/tacticteststandingforwardenemy.h
new file mode 100755
index 0000000..9f81bfd
--- /dev/null
+++ b/src/ai/tactic/tacticteststandingforwardenemy.h
@@ -0,0 +1,25 @@
+#ifndef TACTICTESTSTANDINGFORWARDENEMY_H
+#define TACTICTESTSTANDINGFORWARDENEMY_H
+#include "tactic.h"
+#define DangerDist 300
+#include "geom.h"
+#include "constants.h"
+
+class TacticTestStandingForwardEnemy : public Tactic
+{
+private:
+ //distanse between enemy and ally robot
+ int distance;
+ int OppRobotIndex;
+ Q_OBJECT
+public:
+ TacticTestStandingForwardEnemy();
+ explicit TacticTestStandingForwardEnemy(WorldModel *worldmodel, QObject *parent = 0);
+ virtual RobotCommand getCommand();
+ int getDistance() const;
+ void setDistance(int value);
+ int getOppRobotIndex() const;
+ void setOppRobotIndex(int value);
+};
+
+#endif // TACTICTESTSTANDINGFORWARDENEMY_H
diff --git a/src/ai/tactic/taticgoliealihejazi.cpp b/src/ai/tactic/taticgoliealihejazi.cpp
new file mode 100755
index 0000000..b161aef
--- /dev/null
+++ b/src/ai/tactic/taticgoliealihejazi.cpp
@@ -0,0 +1,16 @@
+#include "taticgoliealihejazi.h"
+
+taticgoliealihejazi::taticgoliealihejazi(WorldModel *worldmodel, QObject *parent) :
+ Tactic("TacticTest", worldmodel, parent)
+{
+}
+
+RobotCommand taticgoliealihejazi::getCommand()
+{
+ RobotCommand rc;
+ if(wm->ball.vel.loc.dist(*new Vector2D(0,0)) < 40){
+ rc.fin_pos.loc = Vector2D(0,0);
+ }
+ return rc;
+}
+
diff --git a/src/ai/tactic/taticgoliealihejazi.h b/src/ai/tactic/taticgoliealihejazi.h
new file mode 100755
index 0000000..9924f5c
--- /dev/null
+++ b/src/ai/tactic/taticgoliealihejazi.h
@@ -0,0 +1,13 @@
+#ifndef TATICGOLIEALIHEJAZI_H
+#define TATICGOLIEALIHEJAZI_H
+#include "tactic.h"
+
+class taticgoliealihejazi : public Tactic
+{
+ Q_OBJECT
+public:
+ explicit taticgoliealihejazi(WorldModel *worldmodel, QObject *parent = 0);
+ virtual RobotCommand getCommand();
+};
+
+#endif // TATICGOLIEALIHEJAZI_H
diff --git a/src/ai/tactics.h b/src/ai/tactics.h
old mode 100644
new mode 100755
index 50d9d2b..ec1f6f8
--- a/src/ai/tactics.h
+++ b/src/ai/tactics.h
@@ -21,5 +21,7 @@
#include "tactic/tacticcontrol.h"
#include "tactic/tactickicklearning.h"
#include "tactic/tacticformation.h"
+//seyed ali hejazi
+#include "tactic/tacticteststandingforwardenemy.h"
#endif // TACTICS_H
diff --git a/src/etc/base.h b/src/etc/base.h
old mode 100644
new mode 100755
diff --git a/src/etc/constants.cpp b/src/etc/constants.cpp
old mode 100644
new mode 100755
index 19a91de..7254c39
--- a/src/etc/constants.cpp
+++ b/src/etc/constants.cpp
@@ -88,6 +88,7 @@ void setup_consts(QString field_size)
goalCircleDEF_R = goalCircle_R + centerCircle_R/2 + 200;
// Ours.
+ //armin sadreddin
ourGoalCenter = Vector2D(MinX, 0);
ourGoalPost_L = Vector2D(MinX, 500);
ourGoalPost_R = Vector2D(MinX, -500);
diff --git a/src/etc/constants.h b/src/etc/constants.h
old mode 100644
new mode 100755
diff --git a/src/etc/settings.h b/src/etc/settings.h
old mode 100644
new mode 100755
diff --git a/src/formation/formation.cpp b/src/formation/formation.cpp
old mode 100644
new mode 100755
diff --git a/src/formation/formation.h b/src/formation/formation.h
old mode 100644
new mode 100755
diff --git a/src/formation/formation_bpn.cpp b/src/formation/formation_bpn.cpp
old mode 100644
new mode 100755
diff --git a/src/formation/formation_bpn.h b/src/formation/formation_bpn.h
old mode 100644
new mode 100755
diff --git a/src/formation/formation_cdt.cpp b/src/formation/formation_cdt.cpp
old mode 100644
new mode 100755
diff --git a/src/formation/formation_cdt.h b/src/formation/formation_cdt.h
old mode 100644
new mode 100755
diff --git a/src/formation/formation_dt.cpp b/src/formation/formation_dt.cpp
old mode 100644
new mode 100755
diff --git a/src/formation/formation_dt.h b/src/formation/formation_dt.h
old mode 100644
new mode 100755
diff --git a/src/formation/formation_knn.cpp b/src/formation/formation_knn.cpp
old mode 100644
new mode 100755
diff --git a/src/formation/formation_knn.h b/src/formation/formation_knn.h
old mode 100644
new mode 100755
diff --git a/src/formation/formation_ngnet.cpp b/src/formation/formation_ngnet.cpp
old mode 100644
new mode 100755
diff --git a/src/formation/formation_ngnet.h b/src/formation/formation_ngnet.h
old mode 100644
new mode 100755
diff --git a/src/formation/formation_rbf.cpp b/src/formation/formation_rbf.cpp
old mode 100644
new mode 100755
diff --git a/src/formation/formation_rbf.h b/src/formation/formation_rbf.h
old mode 100644
new mode 100755
diff --git a/src/formation/formation_sbsp.cpp b/src/formation/formation_sbsp.cpp
old mode 100644
new mode 100755
diff --git a/src/formation/formation_sbsp.h b/src/formation/formation_sbsp.h
old mode 100644
new mode 100755
diff --git a/src/formation/formation_static.cpp b/src/formation/formation_static.cpp
old mode 100644
new mode 100755
diff --git a/src/formation/formation_static.h b/src/formation/formation_static.h
old mode 100644
new mode 100755
diff --git a/src/formation/formation_uva.cpp b/src/formation/formation_uva.cpp
old mode 100644
new mode 100755
diff --git a/src/formation/formation_uva.h b/src/formation/formation_uva.h
old mode 100644
new mode 100755
diff --git a/src/formation/sample_data.cpp b/src/formation/sample_data.cpp
old mode 100644
new mode 100755
diff --git a/src/formation/sample_data.h b/src/formation/sample_data.h
old mode 100644
new mode 100755
diff --git a/src/formation_tools/formation_dt.cpp b/src/formation_tools/formation_dt.cpp
old mode 100644
new mode 100755
diff --git a/src/formation_tools/formation_dt.h b/src/formation_tools/formation_dt.h
old mode 100644
new mode 100755
diff --git a/src/formation_tools/formationdata.cpp b/src/formation_tools/formationdata.cpp
old mode 100644
new mode 100755
diff --git a/src/formation_tools/formationdata.h b/src/formation_tools/formationdata.h
old mode 100644
new mode 100755
diff --git a/src/formation_tools/formationparser.cpp b/src/formation_tools/formationparser.cpp
old mode 100644
new mode 100755
diff --git a/src/formation_tools/formationparser.h b/src/formation_tools/formationparser.h
old mode 100644
new mode 100755
diff --git a/src/geom/angle_deg.cpp b/src/geom/angle_deg.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/angle_deg.h b/src/geom/angle_deg.h
old mode 100644
new mode 100755
diff --git a/src/geom/circle_2d.cpp b/src/geom/circle_2d.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/circle_2d.h b/src/geom/circle_2d.h
old mode 100644
new mode 100755
diff --git a/src/geom/composite_region_2d.cpp b/src/geom/composite_region_2d.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/composite_region_2d.h b/src/geom/composite_region_2d.h
old mode 100644
new mode 100755
diff --git a/src/geom/convex_hull.cpp b/src/geom/convex_hull.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/convex_hull.h b/src/geom/convex_hull.h
old mode 100644
new mode 100755
diff --git a/src/geom/delaunay_triangulation.cpp b/src/geom/delaunay_triangulation.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/delaunay_triangulation.h b/src/geom/delaunay_triangulation.h
old mode 100644
new mode 100755
diff --git a/src/geom/geom.h b/src/geom/geom.h
old mode 100644
new mode 100755
diff --git a/src/geom/line_2d.cpp b/src/geom/line_2d.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/line_2d.h b/src/geom/line_2d.h
old mode 100644
new mode 100755
diff --git a/src/geom/matrix_2d.cpp b/src/geom/matrix_2d.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/matrix_2d.h b/src/geom/matrix_2d.h
old mode 100644
new mode 100755
diff --git a/src/geom/polygon_2d.cpp b/src/geom/polygon_2d.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/polygon_2d.h b/src/geom/polygon_2d.h
old mode 100644
new mode 100755
diff --git a/src/geom/ray_2d.cpp b/src/geom/ray_2d.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/ray_2d.h b/src/geom/ray_2d.h
old mode 100644
new mode 100755
diff --git a/src/geom/rect_2d.cpp b/src/geom/rect_2d.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/rect_2d.h b/src/geom/rect_2d.h
old mode 100644
new mode 100755
diff --git a/src/geom/region_2d.h b/src/geom/region_2d.h
old mode 100644
new mode 100755
diff --git a/src/geom/sector_2d.cpp b/src/geom/sector_2d.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/sector_2d.h b/src/geom/sector_2d.h
old mode 100644
new mode 100755
diff --git a/src/geom/segment_2d.cpp b/src/geom/segment_2d.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/segment_2d.h b/src/geom/segment_2d.h
old mode 100644
new mode 100755
diff --git a/src/geom/size_2d.h b/src/geom/size_2d.h
old mode 100644
new mode 100755
diff --git a/src/geom/triangle_2d.cpp b/src/geom/triangle_2d.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/triangle_2d.h b/src/geom/triangle_2d.h
old mode 100644
new mode 100755
diff --git a/src/geom/triangulation.h b/src/geom/triangulation.h
old mode 100644
new mode 100755
diff --git a/src/geom/vector_2d.cpp b/src/geom/vector_2d.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/vector_2d.h b/src/geom/vector_2d.h
old mode 100644
new mode 100755
diff --git a/src/geom/voronoi_diagram.cpp b/src/geom/voronoi_diagram.cpp
old mode 100644
new mode 100755
diff --git a/src/geom/voronoi_diagram.h b/src/geom/voronoi_diagram.h
old mode 100644
new mode 100755
diff --git a/src/geom2/shape2d.cpp b/src/geom2/shape2d.cpp
old mode 100644
new mode 100755
diff --git a/src/geom2/shape2d.h b/src/geom2/shape2d.h
old mode 100644
new mode 100755
diff --git a/src/kn2cssl_new.pro b/src/kn2cssl_new.pro
old mode 100644
new mode 100755
index c498e74..99c0aae
--- a/src/kn2cssl_new.pro
+++ b/src/kn2cssl_new.pro
@@ -172,6 +172,7 @@ SOURCES += main.cpp \
ai/play/freeKicks/freekick9.cpp \
ai/play/freeKicks/freekick10.cpp \
ai/play/freeKicks/freekick11.cpp \
+ ai/play/freeKicks/freekicktest1.cpp\
ai/play/freeKicks/freekick47.cpp \
etc/constants.cpp \
ssl/sslvision_single.cpp \
@@ -209,7 +210,17 @@ SOURCES += main.cpp \
ai/skill/skillpassreceive.cpp \
ai/skill/skillonetouch.cpp \
ai/tactic/tacticformation.cpp \
- ai/play/playformations.cpp
+ ai/play/playformations.cpp \
+<<<<<<< HEAD
+ ai/tactic/tacticteststandingforwardenemy.cpp \
+ ai/play/playhw2_1.cpp \
+ ai/play/mantomandefense.cpp \
+ ai/tactic/taticgoliealihejazi.cpp \
+ ai/skill/shootball.cpp \
+ ai/play/playstop_hejazi.cpp \
+ ai/play/freeKicks/freekicktest2.cpp
+=======
+>>>>>>> 4bde963eede2897a0748e0221474ee6c1450efde
HEADERS += \
etc/settings.h \
@@ -317,6 +328,7 @@ HEADERS += \
ai/play/freeKicks/freekick9.h \
ai/play/freeKicks/freekick10.h \
ai/play/freeKicks/freekick11.h \
+ ai/play/freeKicks/freekicktest1.h\
ai/play/freeKicks/freekick47.h \
ssl/sslvision_single.h \
ssl/sslvision_double.h \
@@ -354,7 +366,17 @@ HEADERS += \
ai/skill/skillpassreceive.h \
ai/skill/skillonetouch.h \
ai/tactic/tacticformation.h \
- ai/play/playformations.h
+ ai/play/playformations.h \
+<<<<<<< HEAD
+ ai/tactic/tacticteststandingforwardenemy.h \
+ ai/play/playhw2_1.h \
+ ai/play/mantomandefense.h \
+ ai/tactic/taticgoliealihejazi.h \
+ ai/skill/shootball.h \
+ ai/play/playstop_hejazi.h \
+ ai/play/freeKicks/freekicktest2.h
+=======
+>>>>>>> 4bde963eede2897a0748e0221474ee6c1450efde
FORMS += ui/mainwindow.ui
diff --git a/src/kn2cssl_new.pro.user.18 b/src/kn2cssl_new.pro.user.18
new file mode 100644
index 0000000..e193252
--- /dev/null
+++ b/src/kn2cssl_new.pro.user.18
@@ -0,0 +1,271 @@
+
+
+
+
+
+ EnvironmentId
+ {a58473ed-b6ed-4db1-a972-6f88c31ab903}
+
+
+ ProjectExplorer.Project.ActiveTarget
+ 0
+
+
+ ProjectExplorer.Project.EditorSettings
+
+ true
+ false
+ true
+
+ Cpp
+
+ CppGlobal
+
+
+
+ QmlJS
+
+ QmlJSGlobal
+
+
+ 2
+ UTF-8
+ false
+ 4
+ false
+ 80
+ true
+ true
+ 1
+ true
+ false
+ 0
+ true
+ 0
+ 8
+ true
+ 1
+ true
+ true
+ true
+ false
+
+
+
+ ProjectExplorer.Project.PluginSettings
+
+
+
+ ProjectExplorer.Project.Target.0
+
+ Desktop Qt 5.5.0 GCC 64bit
+ Desktop Qt 5.5.0 GCC 64bit
+ qt.55.gcc_64_kit
+ 0
+ 0
+ 0
+
+ /home/sadra/Desktop/kn2cPrograms/build-kn2cssl_new-Desktop_Qt_5_5_0_GCC_64bit-Debug
+
+
+ true
+ qmake
+
+ QtProjectManager.QMakeBuildStep
+ false
+ true
+
+ false
+ false
+ false
+
+
+ true
+ Make
+
+ Qt4ProjectManager.MakeStep
+
+ -w
+ -r
+
+ false
+ -j4 -l4
+
+
+ 2
+ Build
+
+ ProjectExplorer.BuildSteps.Build
+
+
+
+ true
+ Make
+
+ Qt4ProjectManager.MakeStep
+
+ -w
+ -r
+
+ true
+ clean
+
+
+ 1
+ Clean
+
+ ProjectExplorer.BuildSteps.Clean
+
+ 2
+ false
+
+ Debug
+
+ Qt4ProjectManager.Qt4BuildConfiguration
+ 2
+ true
+
+
+ /home/sadra/Desktop/kn2cPrograms/build-kn2cssl_new-Desktop_Qt_5_5_0_GCC_64bit-Release
+
+
+ true
+ qmake
+
+ QtProjectManager.QMakeBuildStep
+ false
+ true
+
+ false
+ false
+ false
+
+
+ true
+ Make
+
+ Qt4ProjectManager.MakeStep
+
+ -w
+ -r
+
+ false
+
+
+
+ 2
+ Build
+
+ ProjectExplorer.BuildSteps.Build
+
+
+
+ true
+ Make
+
+ Qt4ProjectManager.MakeStep
+
+ -w
+ -r
+
+ true
+ clean
+
+
+ 1
+ Clean
+
+ ProjectExplorer.BuildSteps.Clean
+
+ 2
+ false
+
+ Release
+
+ Qt4ProjectManager.Qt4BuildConfiguration
+ 0
+ true
+
+ 2
+
+
+ 0
+ Deploy
+
+ ProjectExplorer.BuildSteps.Deploy
+
+ 1
+ Deploy locally
+
+ ProjectExplorer.DefaultDeployConfiguration
+
+ 1
+
+
+
+ false
+ false
+ false
+ false
+ true
+ 0.01
+ 10
+ true
+ 1
+ 25
+
+ 1
+ true
+ false
+ true
+ valgrind
+
+ 0
+ 1
+ 2
+ 3
+ 4
+ 5
+ 6
+ 7
+ 8
+ 9
+ 10
+ 11
+ 12
+ 13
+ 14
+
+ 2
+
+ kn2cssl_new
+
+ Qt4ProjectManager.Qt4RunConfiguration:/home/sadra/Desktop/kn2cPrograms/src/kn2cssl_new.pro
+
+ kn2cssl_new.pro
+ false
+ false
+
+ 3768
+ false
+ true
+ false
+ false
+ true
+
+ 1
+
+
+
+ ProjectExplorer.Project.TargetCount
+ 1
+
+
+ ProjectExplorer.Project.Updater.FileVersion
+ 18
+
+
+ Version
+ 18
+
+
diff --git a/src/kn2cssl_new.pro.user.a075b2b b/src/kn2cssl_new.pro.user.a075b2b
new file mode 100644
index 0000000..4ab1656
--- /dev/null
+++ b/src/kn2cssl_new.pro.user.a075b2b
@@ -0,0 +1,260 @@
+
+
+
+
+
+ ProjectExplorer.Project.ActiveTarget
+ 0
+
+
+ ProjectExplorer.Project.EditorSettings
+
+ true
+ false
+ true
+
+ Cpp
+
+ CppGlobal
+
+
+
+ QmlJS
+
+ QmlJSGlobal
+
+
+ 2
+ UTF-8
+ false
+ 4
+ false
+ true
+ 1
+ true
+ 0
+ true
+ 0
+ 8
+ true
+ 1
+ true
+ true
+ true
+ false
+
+
+
+ ProjectExplorer.Project.PluginSettings
+
+
+
+ ProjectExplorer.Project.Target.0
+
+ Desktop Qt 5.2.1 GCC 64bit
+ Desktop Qt 5.2.1 GCC 64bit
+ qt.521.gcc_64.essentials_kit
+ 0
+ 0
+ 0
+
+ /home/arminsadreddin/ssl-main-code/Robotic/kn2cPrograms/build-kn2cssl_new-Desktop_Qt_5_2_1_GCC_64bit-Debug
+
+
+ true
+ qmake
+
+ QtProjectManager.QMakeBuildStep
+ false
+ true
+
+ false
+
+
+ true
+ Make
+
+ Qt4ProjectManager.MakeStep
+
+ -w
+ -r
+
+ false
+
+
+
+ 2
+ Build
+
+ ProjectExplorer.BuildSteps.Build
+
+
+
+ true
+ Make
+
+ Qt4ProjectManager.MakeStep
+
+ -w
+ -r
+
+ true
+ clean
+
+
+ 1
+ Clean
+
+ ProjectExplorer.BuildSteps.Clean
+
+ 2
+ false
+
+ Debug
+
+ Qt4ProjectManager.Qt4BuildConfiguration
+ 2
+ true
+
+
+ /home/arminsadreddin/ssl-main-code/Robotic/kn2cPrograms/build-kn2cssl_new-Desktop_Qt_5_2_1_GCC_64bit-Release
+
+
+ true
+ qmake
+
+ QtProjectManager.QMakeBuildStep
+ false
+ true
+
+ false
+
+
+ true
+ Make
+
+ Qt4ProjectManager.MakeStep
+
+ -w
+ -r
+
+ false
+
+
+
+ 2
+ Build
+
+ ProjectExplorer.BuildSteps.Build
+
+
+
+ true
+ Make
+
+ Qt4ProjectManager.MakeStep
+
+ -w
+ -r
+
+ true
+ clean
+
+
+ 1
+ Clean
+
+ ProjectExplorer.BuildSteps.Clean
+
+ 2
+ false
+
+ Release
+
+ Qt4ProjectManager.Qt4BuildConfiguration
+ 0
+ true
+
+ 2
+
+
+ 0
+ Deploy
+
+ ProjectExplorer.BuildSteps.Deploy
+
+ 1
+ Deploy locally
+
+ ProjectExplorer.DefaultDeployConfiguration
+
+ 1
+
+
+
+ false
+ false
+ false
+ false
+ true
+ 0.01
+ 10
+ true
+ 1
+ 25
+
+ 1
+ true
+ false
+ true
+ valgrind
+
+ 0
+ 1
+ 2
+ 3
+ 4
+ 5
+ 6
+ 7
+ 8
+ 9
+ 10
+ 11
+ 12
+ 13
+ 14
+
+ 2
+
+ kn2cssl_new
+
+ Qt4ProjectManager.Qt4RunConfiguration:/home/arminsadreddin/ssl-main-code/Robotic/kn2cPrograms/src/kn2cssl_new.pro
+
+ kn2cssl_new.pro
+ false
+ false
+
+ 3768
+ true
+ false
+ false
+ false
+ true
+
+ 1
+
+
+
+ ProjectExplorer.Project.TargetCount
+ 1
+
+
+ ProjectExplorer.Project.Updater.EnvironmentId
+ {a075b2b7-f436-4b42-b1f9-98e0216d7710}
+
+
+ ProjectExplorer.Project.Updater.FileVersion
+ 15
+
+
diff --git a/src/kn2cssl_new.pro.user.a58473e b/src/kn2cssl_new.pro.user.a58473e
new file mode 100644
index 0000000..83c4924
--- /dev/null
+++ b/src/kn2cssl_new.pro.user.a58473e
@@ -0,0 +1,260 @@
+
+
+
+
+
+ ProjectExplorer.Project.ActiveTarget
+ 0
+
+
+ ProjectExplorer.Project.EditorSettings
+
+ true
+ false
+ true
+
+ Cpp
+
+ CppGlobal
+
+
+
+ QmlJS
+
+ QmlJSGlobal
+
+
+ 2
+ UTF-8
+ false
+ 4
+ false
+ true
+ 1
+ true
+ 0
+ true
+ 0
+ 8
+ true
+ 1
+ true
+ true
+ true
+ false
+
+
+
+ ProjectExplorer.Project.PluginSettings
+
+
+
+ ProjectExplorer.Project.Target.0
+
+ Desktop Qt 5.2.1 GCC 64bit
+ Desktop Qt 5.2.1 GCC 64bit
+ qt.521.gcc_64.essentials_kit
+ 0
+ 0
+ 0
+
+ /home/sadra/Desktop/kn2cPrograms/build-kn2cssl_new-Desktop_Qt_5_2_1_GCC_64bit-Debug
+
+
+ true
+ qmake
+
+ QtProjectManager.QMakeBuildStep
+ false
+ true
+
+ false
+
+
+ true
+ Make
+
+ Qt4ProjectManager.MakeStep
+
+ -w
+ -r
+
+ false
+ -j4 -l4
+
+
+ 2
+ Build
+
+ ProjectExplorer.BuildSteps.Build
+
+
+
+ true
+ Make
+
+ Qt4ProjectManager.MakeStep
+
+ -w
+ -r
+
+ true
+ clean
+
+
+ 1
+ Clean
+
+ ProjectExplorer.BuildSteps.Clean
+
+ 2
+ false
+
+ Debug
+
+ Qt4ProjectManager.Qt4BuildConfiguration
+ 2
+ true
+
+
+ /home/sadra/Desktop/kn2cPrograms/build-kn2cssl_new-Desktop_Qt_5_2_1_GCC_64bit-Release
+
+
+ true
+ qmake
+
+ QtProjectManager.QMakeBuildStep
+ false
+ true
+
+ false
+
+
+ true
+ Make
+
+ Qt4ProjectManager.MakeStep
+
+ -w
+ -r
+
+ false
+
+
+
+ 2
+ Build
+
+ ProjectExplorer.BuildSteps.Build
+
+
+
+ true
+ Make
+
+ Qt4ProjectManager.MakeStep
+
+ -w
+ -r
+
+ true
+ clean
+
+
+ 1
+ Clean
+
+ ProjectExplorer.BuildSteps.Clean
+
+ 2
+ false
+
+ Release
+
+ Qt4ProjectManager.Qt4BuildConfiguration
+ 0
+ true
+
+ 2
+
+
+ 0
+ Deploy
+
+ ProjectExplorer.BuildSteps.Deploy
+
+ 1
+ Deploy locally
+
+ ProjectExplorer.DefaultDeployConfiguration
+
+ 1
+
+
+
+ false
+ false
+ false
+ false
+ true
+ 0.01
+ 10
+ true
+ 1
+ 25
+
+ 1
+ true
+ false
+ true
+ valgrind
+
+ 0
+ 1
+ 2
+ 3
+ 4
+ 5
+ 6
+ 7
+ 8
+ 9
+ 10
+ 11
+ 12
+ 13
+ 14
+
+ 2
+
+ kn2cssl_new
+
+ Qt4ProjectManager.Qt4RunConfiguration:/home/sadra/Desktop/kn2cPrograms/src/kn2cssl_new.pro
+
+ kn2cssl_new.pro
+ false
+ false
+
+ 3768
+ true
+ false
+ false
+ false
+ true
+
+ 1
+
+
+
+ ProjectExplorer.Project.TargetCount
+ 1
+
+
+ ProjectExplorer.Project.Updater.EnvironmentId
+ {a58473ed-b6ed-4db1-a972-6f88c31ab903}
+
+
+ ProjectExplorer.Project.Updater.FileVersion
+ 15
+
+
diff --git a/src/logplayer/ai_logplayer.cpp b/src/logplayer/ai_logplayer.cpp
old mode 100644
new mode 100755
diff --git a/src/logplayer/ai_logplayer.h b/src/logplayer/ai_logplayer.h
old mode 100644
new mode 100755
diff --git a/src/logplayer/logplayer.cpp b/src/logplayer/logplayer.cpp
old mode 100644
new mode 100755
diff --git a/src/logplayer/logplayer.h b/src/logplayer/logplayer.h
old mode 100644
new mode 100755
diff --git a/src/logplayer/referee_logplayer.cpp b/src/logplayer/referee_logplayer.cpp
old mode 100644
new mode 100755
diff --git a/src/logplayer/referee_logplayer.h b/src/logplayer/referee_logplayer.h
old mode 100644
new mode 100755
diff --git a/src/logplayer/vision_logplayer.cpp b/src/logplayer/vision_logplayer.cpp
old mode 100644
new mode 100755
diff --git a/src/logplayer/vision_logplayer.h b/src/logplayer/vision_logplayer.h
old mode 100644
new mode 100755
diff --git a/src/main.cpp b/src/main.cpp
old mode 100644
new mode 100755
diff --git a/src/output/agent.cpp b/src/output/agent.cpp
new file mode 100644
index 0000000..e49032a
--- /dev/null
+++ b/src/output/agent.cpp
@@ -0,0 +1,108 @@
+#include "agent.h"
+#include "worldmodel.h"
+
+Agent::Agent() :
+ Robot()
+{
+ wm = 0;
+ id = -1;
+}
+
+void Agent::setID(int id)
+{
+ this->id = id;
+ nav.setID(id);
+}
+
+void Agent::setWorldModel(WorldModel *wm)
+{
+ this->wm = wm;
+ nav.setWorldModel(wm);
+}
+
+void Agent::setOutputBuffer(OutputBuffer *outputBuffer)
+{
+ this->outputBuffer = outputBuffer;
+}
+
+void Agent::SendCommand(RobotCommand rc)
+{
+ if(!wm->ourRobot[id].isValid) return;
+
+ if( id == 0 ) wm->debug_pos.clear();
+ ControllerInput ci = nav.calc(rc);
+ if( id == 0 )
+ {
+ 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.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;
+ grRD.velw = co.rs.VW;
+ grRD.wheel1 = co.msS.M0;
+ grRD.wheel2 = co.msS.M1;
+ grRD.wheel3 = co.msS.M2;
+ grRD.wheel4 = co.msS.M3;
+ grRD.kickspeedx = rc.kickspeedx;
+ grRD.kickspeedz = rc.kickspeedz;
+ grRD.spinner = 0;
+ if( grSimPacketIsValid(grRD) )
+ outputBuffer->grpck.AddRobot(grRD);
+}
+
+void Agent::Halt()
+{
+ // Real Game Packet
+ RobotData reRD;
+ reRD.RID = id;
+ reRD.M0 = 0;
+ reRD.M1 = 0;
+ reRD.M2 = 0;
+ reRD.M3 = 0;
+ reRD.KCK = 0;
+ reRD.CHP = 0;
+ outputBuffer->wpck.AddRobot(reRD);
+ // grSim Packet
+ grRobotData grRD;
+ grRD.rid=id;
+ grRD.velx = 0;
+ grRD.vely = 0;
+ grRD.velw = 0;
+ grRD.wheel1=0;
+ grRD.wheel2=0;
+ grRD.wheel3=0;
+ grRD.wheel4=0;
+ grRD.kickspeedx=0;
+ grRD.kickspeedz=0;
+ grRD.spinner=0;
+ outputBuffer->grpck.AddRobot(grRD);
+}
+
+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;
+
+}
+
diff --git a/src/output/agent.h b/src/output/agent.h
new file mode 100644
index 0000000..1919a2b
--- /dev/null
+++ b/src/output/agent.h
@@ -0,0 +1,94 @@
+#ifndef AGENT_H
+#define AGENT_H
+
+#include
+#include "robot.h"
+#include "robotcommand.h"
+#include "navigation.h"
+
+enum AgentStatus
+{
+ Idle,
+ Passing,
+ Kicking,
+ Chiping,
+ FollowingBall,
+ BlockingBall,
+ BlockingRobot,
+ RecievingPass,
+ OneTouch
+};
+
+enum AgentRole
+{
+ NoRole = 0,
+ ArcMid,
+ ArcLeft,
+ ArcRight,
+ FixedPositionLeft,
+ FixedPositionRight,
+ FixedPositionMid,
+ AttackerLeft,
+ AttackerRight,
+ AttackerMid,
+ Blocker,
+ DefenderLeft,
+ DefenderRight,
+ DefenderMid,
+ Golie
+};
+
+enum AgentRegion
+{
+ NoRegion,
+ Left,
+ Center,
+ Right
+};
+
+struct Marking_Struct
+{
+ int ourI;
+ int oppI;
+};
+
+struct Positioning_Struct
+{
+ int ourI;
+ Vector2D loc;
+};
+
+class WorldModel;
+
+class Agent : public Robot
+{
+ Q_OBJECT
+public:
+ explicit Agent();
+ void setID(int id);
+ void setWorldModel(WorldModel *wm);
+ void setOutputBuffer(OutputBuffer *outputBuffer);
+
+ void SendCommand(RobotCommand rc);
+ void Halt();
+
+ AgentRole Role;
+ AgentStatus Status;
+ AgentRegion Region;
+
+ RobotData rd; //received data from robot
+ Position vel2; //speed from motors speed received from robot
+
+private:
+ int id;
+ Controller ctrl;
+ Navigation nav;
+ OutputBuffer *outputBuffer;
+ WorldModel *wm;
+
+ bool grSimPacketIsValid(grRobotData grRD);
+ bool controllerResultIsValid(ControllerResult co);
+
+};
+
+#endif // AGENT_H
diff --git a/src/output/controller.cpp b/src/output/controller.cpp
index f05fc3a..2a29674 100644
--- a/src/output/controller.cpp
+++ b/src/output/controller.cpp
@@ -1,6 +1,5 @@
#include "controller.h"
#include "constants.h"
-#include "math.h"
#define ROBOTRADIUS 0.090
#define SpeedToRPMR 5000
@@ -14,12 +13,14 @@ Controller::Controller(QObject *parent) :
timer.start();
+
err0 = {0,0};
err1 = {0,0};
u1 = {0,0};
derived0 = {0,0};
derived1 = {0,0};
integral = {0,0};
+ last_setpoint = {0,0};
wu1 = 0;
wu1_last = 0;
@@ -46,13 +47,14 @@ ControllerResult Controller::calc(ControllerInput &ci)
//ctrlresult.rs = calcRobotSpeed_test(ci);
//qDebug() << "id" << ci.id << "timer" << time;
- // ctrlresult.msR = calcReal(ctrlresult.rs);
- ctrlresult.msS = calcSimul(ctrlresult.rs,ci);
+ ctrlresult.msR = calcReal(ctrlresult.rs);
+ ctrlresult.msS = calcSimul(ctrlresult.rs);
return ctrlresult;
}
RobotSpeed Controller::calcRobotSpeed_main(ControllerInput &ci)
{
+<<<<<<< HEAD
RobotSpeed setpoint;
Vector2D speed_sp;
@@ -61,24 +63,24 @@ RobotSpeed Controller::calcRobotSpeed_main(ControllerInput &ci)
// //! Test
-// if(fabs(Vector2D(ci.cur_pos.loc-Vector2D( 2400,-2000)).r()) < 1000 )
-// //if(ci.cur_pos.loc.x > -1000)
-// wu1=0;
-// if(fabs(Vector2D(ci.cur_pos.loc-Vector2D( 2400, 2000)).r()) < 1000 )
-// //if(ci.cur_pos.loc.x < -3800)
-// wu1=1;
+ if(fabs(Vector2D(ci.cur_pos.loc-Vector2D( 2400,-2000)).r()) < 1000 )
+ //if(ci.cur_pos.loc.x > -1000)
+ wu1=0;
+ if(fabs(Vector2D(ci.cur_pos.loc-Vector2D( 2400, 2000)).r()) < 1000 )
+ //if(ci.cur_pos.loc.x < -3800)
+ wu1=1;
-// ci.mid_pos.loc.x = 2400;
-// ci.mid_pos.dir = M_PI;
+ ci.mid_pos.loc.x = 2400;
+ ci.mid_pos.dir = M_PI;
-// if(wu1==0)
-// ci.mid_pos.loc.y = 2860;
-// //setpoint.VX = -2;
-// else
-// //setpoint.VX = 2;
-// ci.mid_pos.loc.y = -2860;
+ if(wu1==0)
+ ci.mid_pos.loc.y = 2860;
+ //setpoint.VX = -2;
+ else
+ //setpoint.VX = 2;
+ ci.mid_pos.loc.y = -2860;
// //! test
@@ -226,21 +228,400 @@ RobotSpeed Controller::calcRobotSpeed_main(ControllerInput &ci)
// setpoint.VY=0;
// setpoint.VW=0;
return setpoint;
+=======
+ //double time = timer.elapsed()/1000;
+ //timer.restart();
+ /******************************Linear Speed Controller************************************/
+ err1 = (ci.mid_pos.loc - ci.cur_pos.loc)*.001;
+
+// if(ci.maxSpeed == 3)
+// ci.maxSpeed == 4;
+
+
+ ///!
+// if((ci.mid_pos.loc - last_setpoint ).length() > 30)
+// {
+//// qDebug() <<"L"< 1.5)
+ {
+ kp = fabs(err1.length());
+ ki = 0.01;
+ kd = 3;
+ integral = integral + err1*AI_TIMER/1000.0 ;
+ }
+ else /*if(err > .04)*/
+ {
+ integral.scale(0);
+ if(ci.fin_pos.loc == ci.mid_pos.loc)
+ {
+ kp = 5-2*fabs(ci.cur_vel.loc.length());fabs(err1.length())+2.9;////day2//f
+ if((ci.mid_pos.loc - last_setpoint ).length() > 30)
+ {
+ ki=.3;
+ }
+ last_setpoint = ci.mid_pos.loc;
+ }
+ else
+ {
+ kp = 4;
+ }
+ kd = 3;
+
+ }
+
+
+
+
+ derived1 = (ci.cur_vel.loc - derived0)*0.1;
+ derived0 = ci.cur_vel.loc;
+
+
+
+ LinearSpeed = err1*kp + integral*ki*err - derived1*kd;
+
+
+// ////////////////////////////////////////day2
+ double diff_angel = ci.cur_vel.dir - LinearSpeed.dir().radian();
+ if (diff_angel > M_PI) diff_angel -= 2 * M_PI;
+ if (diff_angel < -M_PI) diff_angel += 2 * M_PI;
+ if(fabs(diff_angel) > M_PI*0.7)
+ {
+ LinearSpeed = LinearSpeed_past + (LinearSpeed - LinearSpeed_past)*0.01;//*50/(ci.mid_pos.loc - last_setpoint).length();
+
+ if(ci.id==8)
+ qDebug()<<"filter"<<(ci.mid_pos.loc - last_setpoint).length();
+ }
+ LinearSpeed_past = LinearSpeed ;
+// ////////////////////////////////////////day2
+
+ if(LinearSpeed.length()>ci.maxSpeed)
+ {
+ LinearSpeed.setLength(ci.maxSpeed);
+ }
+
+ if(ci.id == 8)
+ qDebug()< M_PI) werr1 -= 2 * M_PI;
+ if (werr1 < -M_PI) werr1 += 2 * M_PI;
+
+ double werr = fabs(werr1);
+
+
+ //wki=0.003*fabs(werr0);
+ //wintegral = wintegral + werr1*AI_TIMER;
+
+ wkp=1*fabs(werr0);//0.3;
+ wkd=1;
+ if(werr<.3 + 10*fabs(ci.cur_vel.dir))
+ {
+ wintegral=0;
+ //wintegral = wintegral - 3*werr1*AI_TIMER;
+
+ wkp=0.4;
+ wkd=0.003;
+ }
+
+
+
+ //if(ci.id == 3)
+ //qDebug()<MAXROTATIONSPEED)
+ {
+ wintegral = wintegral - werr1*AI_TIMER;
+ wu1=MAXROTATIONSPEED*sign(wu1);
+ }
+
+ RotationSpeed = wu1;
+
+
+ double alpha = ci.cur_pos.dir ;+atan(RotationSpeed*0.187);
+ //alpha is the corrected angel whitch handle the problem
+ //of nonlinear relation of rotational movement and linear movement
+
+
+
+
+ RotLinearSpeed.x = LinearSpeed.x * cos(alpha) + LinearSpeed.y * sin(alpha);
+ RotLinearSpeed.y = -LinearSpeed.x * sin(alpha) + LinearSpeed.y * cos(alpha);
+
+ RobotSpeed ans;
+
+ ans.VX = RotLinearSpeed.x;
+ ans.VY = RotLinearSpeed.y;
+ ans.VW = RotationSpeed ;
+
+ if(werr <0.07 /*&& err1.length()<.015*/) ans.VW=0;//maximum priscision in angel for robot becuse of it/s phisic's limits is 0.07 rad
+
+
+ if(err1.length()<.02)
+ {
+ ans.VX=0;
+ ans.VY=0;
+ }
+
+ return ans;
}
+RobotSpeed Controller::calcRobotSpeed_adjt(ControllerInput &ci)
+{
+ float RotationSpeed;
+ RotationSpeed = wu1;
+ Vector2D RotLinearSpeed;
+ switch(stateCTRL)
+ {
+ case 0://jelo
+ RotationSpeed = 0;
+ werr1 = ((Vector2D(1500,0)-ci.cur_pos.loc).dir().radian()) - ci.cur_pos.dir;
+ if (werr1 > M_PI) werr1 -= 2 * M_PI;
+ if (werr1 < -M_PI) werr1 += 2 * M_PI;
+ RotLinearSpeed = Vector2D(1.5,0);//sorate robot jelo
+ if((Vector2D(1500,0) - ci.cur_pos.loc).length()>500 && fabs(werr1)>M_PI/2.0)
+ {
+ stateCTRL = 3;
+ }
+ break;
+ case 1://aghab
+ RotationSpeed = 0;
+ werr1 = ((Vector2D(1500,0)-ci.cur_pos.loc).dir().radian()) - ci.cur_pos.dir;
+ if (werr1 > M_PI) werr1 -= 2 * M_PI;
+ if (werr1 < -M_PI) werr1 += 2 * M_PI;
+ RotLinearSpeed = Vector2D(-.3,0);//sorate robot aghab
+ if((Vector2D(1500,0) - ci.cur_pos.loc).length()>500&& fabs(werr1) M_PI) werr1 -= 2 * M_PI;
+ if (werr1 < -M_PI) werr1 += 2 * M_PI;
+
+ if(werr1<-(M_PI/18.0))
+ {
+ RotationSpeed = -1;
+ }
+ else if(werr1>(M_PI/18.0))
+ {
+ RotationSpeed = 1;
+ }
+ else
+ {
+ RotationSpeed = 0;
+ stateCTRL = 0;
+ }
+
+ break;
+ case 3://charkhesh
+ RotLinearSpeed = Vector2D(0,0);
+ werr1 = ((Vector2D(1200,0)-ci.cur_pos.loc).dir().radian() + M_PI) - ci.cur_pos.dir;
+ if (werr1 > M_PI) werr1 -= 2 * M_PI;
+ if (werr1 < -M_PI) werr1 += 2 * M_PI;
+
+ if(werr1<-(M_PI/18.0))
+ {
+ RotationSpeed = -1;
+ }
+ else if(werr1>(M_PI/18.0))
+ {
+ RotationSpeed = 1;
+ }
+ else
+ {
+ RotationSpeed = 0;
+ stateCTRL = 1;
+ }
+ break;
+ }
+
+
+ RobotSpeed ans;
+
+ ans.VX = RotLinearSpeed.x;
+ ans.VY = RotLinearSpeed.y;
+ ans.VW = RotationSpeed;
+
+ return ans;
+>>>>>>> 4bde963eede2897a0748e0221474ee6c1450efde
+}
-MotorSpeed Controller::calcSimul(RobotSpeed rs, ControllerInput &ci)
+RobotSpeed Controller::calcRobotSpeed_test(ControllerInput &ci)
{
- double motor[4][1],rotate[4][3],speed[3][1];
+ float RotationSpeed;
+
+ double ap=1;
+ double am=1;
+ double am2=1;
+ double t0;
+ //double t1,t2;
+ double s0;
+ double s3;
+ double s1;
+ double v,dt,s,sp,vb;
+ double tp;
+ double t2p;
+ double t3;
+ /******************************Linear Speed Controller************************************/
Vector2D RotLinearSpeed;
- RotLinearSpeed.x = rs.VX * cos(ci.cur_pos.dir) + rs.VY * sin(ci.cur_pos.dir);
- RotLinearSpeed.y = -rs.VX * sin(ci.cur_pos.dir) + rs.VY * cos(ci.cur_pos.dir);
+ err0 = err1;
+ err1 = (ci.fin_pos.loc - ci.cur_pos.loc)*.001;
+
+ t0 = -ci.cur_vel.loc.length()/ap;
+ s0 = -ci.cur_vel.loc.length()*t0/2;
+ s3 = pow(ci.fin_vel.loc.length(),2)/(2*am);
+ v = 0;//sqrt(s1*2*ap);
+ tp = (v/ap)+t0;
+ t3 = (v/am) + tp;
+ t2p = t3 - (ci.fin_vel.loc.length()/am);
+
+ if(v>ci.maxSpeed)
+ {
+ s = err1.length() + s0 + s3;
+ sp = s * pow((v-ci.maxSpeed)/v,2);
+ dt = sp/ci.maxSpeed;
+ t3 = t3 + dt;
+ t2p = t2p + dt;
+ }
+
+ double dist;
+ vb=ci.maxSpeed/2.0;
+ if (ci.cur_vel.loc.length()dist)
+ {
+ t0 = -ci.cur_vel.loc.length()/ap;
+
+ s0 = -ci.cur_vel.loc.length()*t0/2;
+ s3 = pow(ci.fin_vel.loc.length(),2)/(2*am);
+ s1 = (err1.length()+s0+s3)/(1+ap/am);
+ v = sqrt(s1*2*ap);
+ tp = (v/ap)+t0;
+ t3 = (v/am) + tp;
+ t2p = t3 - (ci.fin_vel.loc.length()/am);
+ //t2 = t2p;
+ double Sm = (pow(v,2)-pow(ci.fin_vel.loc.length(),2))/(2.0*am);
+ u1.setLength(sqrt(2.0*ap*((err1.length()-Sm))+pow(v,2)));
+
+ }
+
+ if(u1.length()>ci.maxSpeed)
+ {
+ u1.setLength(ci.maxSpeed);
+ }
+ Vector2D LinearSpeed;
+
+ LinearSpeed = u1;
+
+ RotLinearSpeed.x = LinearSpeed.x * cos(ci.cur_pos.dir) + LinearSpeed.y * sin(ci.cur_pos.dir);
+ RotLinearSpeed.y = -LinearSpeed.x * sin(ci.cur_pos.dir) + LinearSpeed.y * cos(ci.cur_pos.dir);
+ RotationSpeed=0;
+ RobotSpeed result;
+
+ result.VX = RotLinearSpeed.x;
+ result.VY = RotLinearSpeed.y;
+ result.VW = RotationSpeed;
+
+ out << err1.y <<" "<< LinearSpeed.x <<" "<< LinearSpeed.y << endl;
+ return result;
+}
+
+MotorSpeed Controller::calcReal(RobotSpeed rs)
+{
+ double motor[4][1],rotate[4][3],speed[3][1];
+
+ speed[0][0] = -rs.VX;
+ speed[1][0] = -rs.VY;
+ speed[2][0] = -rs.VW;
+
+ rotate[0][0] = cos( 0.18716 * M_PI);//cos(M_PI /4.0);//-sin(rangle + M_PI);//7/4
+ rotate[1][0] = sin( M_PI / 4.0 );//-cos(0.22 * M_PI);//-sin(rangle - M_PI / 3);//0.218
+ rotate[2][0] = -cos( M_PI / 4.0 );//-sin(0.22 * M_PI);//-sin(rangle + M_PI / 3);//0.78
+ rotate[3][0] = -cos( 0.18716 * M_PI);//cos(M_PI /4.0);//-sin(rangle + M_PI);//5/4
+ rotate[0][1] = -sin(0.18716 * M_PI );//cos(M_PI /4.0);//cos(rangle + M_PI);//7/4
+ rotate[1][1] = cos(M_PI / 4.0 );//- sin(0.22 * M_PI);// cos(rangle - M_PI / 3);//0.218
+ rotate[2][1] = sin(M_PI / 4.0);//cos(0.22 * M_PI);//cos(rangle + M_PI / 3);//0.187
+ rotate[3][1] = -sin(0.18716 * M_PI);//-cos(M_PI /4.0);//cos(rangle + M_PI);//5/4
+
+ rotate[0][2] = -ROBOTRADIUS;
+ rotate[1][2] = -ROBOTRADIUS;
+ rotate[2][2] = -ROBOTRADIUS;
+ rotate[3][2] = -ROBOTRADIUS;
+
+ motor[0][0] = (rotate[0][0] * speed[0][0] + rotate[0][1] * speed[1][0])*SpeedToRPM + rotate[0][2] * speed[2][0]*SpeedToRPMR;
+ motor[1][0] = (rotate[1][0] * speed[0][0] + rotate[1][1] * speed[1][0])*SpeedToRPM + rotate[1][2] * speed[2][0]*SpeedToRPMR;
+ motor[2][0] = (rotate[2][0] * speed[0][0] + rotate[2][1] * speed[1][0])*SpeedToRPM + rotate[2][2] * speed[2][0]*SpeedToRPMR;
+ motor[3][0] = (rotate[3][0] * speed[0][0] + rotate[3][1] * speed[1][0])*SpeedToRPM + rotate[3][2] * speed[2][0]*SpeedToRPMR;
+
+ MotorSpeed result;
+
+ result.M0 = (motor[0][0]);
+ result.M1 = (motor[1][0]);
+ result.M2 = (motor[2][0]);
+ result.M3 = (motor[3][0]);
+
+ return result;
+}
+
+MotorSpeed Controller::calcSimul(RobotSpeed rs)
+{
+ double motor[4][1],rotate[4][3],speed[3][1];
- speed[0][0] = RotLinearSpeed.x/10;
- speed[1][0] = RotLinearSpeed.y/10;
- speed[2][0] = rs.VW/10;
+ speed[0][0] = rs.VX;
+ speed[1][0] = rs.VY;
+ speed[2][0] = rs.VW;
rotate[0][0] = sin(M_PI / 3);//-sin(rangle - M_PI / 3);
rotate[1][0] = sin(3 * M_PI / 4);//-sin(rangle + M_PI / 3);
diff --git a/src/output/controller.h b/src/output/controller.h
index 5062fd5..4193952 100644
--- a/src/output/controller.h
+++ b/src/output/controller.h
@@ -18,7 +18,11 @@ class Controller : public QObject
QTime timer;
RobotSpeed calcRobotSpeed_main(ControllerInput &ci);
- MotorSpeed calcSimul(RobotSpeed rs, ControllerInput &ci);
+ RobotSpeed calcRobotSpeed_adjt(ControllerInput &ci);
+ RobotSpeed calcRobotSpeed_test(ControllerInput &ci);
+
+ MotorSpeed calcReal(RobotSpeed rs);
+ MotorSpeed calcSimul(RobotSpeed rs);
private:
@@ -34,14 +38,6 @@ class Controller : public QObject
double wu1,wu1_last,wintegral,werr0,werr1;
double wderived0,wderived1;
-
- ///////////////////////////////////////////////////////////////new controller
- double wp,wi,wd;
- Vector2D p,i,d,i_near,i_far;
- int fault_counter;
- ///////////////////////////////////////////////////////////////
-
-
int stateCTRL;
ofstream out;
diff --git a/src/output/controller_struct.h b/src/output/controller_struct.h
index 3f585d1..f0a68e5 100644
--- a/src/output/controller_struct.h
+++ b/src/output/controller_struct.h
@@ -17,7 +17,6 @@ struct ControllerInput
int id;
Position cur_pos;
Position cur_vel;
- Position last_vel;
Position mid_pos;
Position mid_vel;
diff --git a/src/output/grpacket.cpp b/src/output/grpacket.cpp
old mode 100644
new mode 100755
diff --git a/src/output/grpacket.h b/src/output/grpacket.h
old mode 100644
new mode 100755
diff --git a/src/output/grsim.cpp b/src/output/grsim.cpp
old mode 100644
new mode 100755
diff --git a/src/output/grsim.h b/src/output/grsim.h
old mode 100644
new mode 100755
diff --git a/src/output/outputbuffer.h b/src/output/outputbuffer.h
old mode 100644
new mode 100755
diff --git a/src/output/transmitter.cpp b/src/output/transmitter.cpp
old mode 100644
new mode 100755
diff --git a/src/output/transmitter.h b/src/output/transmitter.h
old mode 100644
new mode 100755
diff --git a/src/output/wpacket.cpp b/src/output/wpacket.cpp
index e98a235..17f98c7 100644
--- a/src/output/wpacket.cpp
+++ b/src/output/wpacket.cpp
@@ -22,14 +22,11 @@ QByteArray WPacket::GetPacket()
for(int i=0; i<_rdata.size(); i++)
{
- _rdata[i].Vx_sp = qToBigEndian(_rdata[i].Vx_sp);
- _rdata[i].Vy_sp = qToBigEndian(_rdata[i].Vy_sp);
- _rdata[i].Wr_sp = qToBigEndian(_rdata[i].Wr_sp);
- _rdata[i].Vx = qToBigEndian(_rdata[i].Vx);
- _rdata[i].Vy = qToBigEndian(_rdata[i].Vy);
- _rdata[i].Wr = qToBigEndian(_rdata[i].Wr);
- _rdata[i].alpha = qToBigEndian(_rdata[i].alpha);
- rd.append((const char*)&(_rdata[i]), 18); //sizeof(RobotData);
+ _rdata[i].M0 = qToBigEndian(_rdata[i].M0);
+ _rdata[i].M1 = qToBigEndian(_rdata[i].M1);
+ _rdata[i].M2 = qToBigEndian(_rdata[i].M2);
+ _rdata[i].M3 = qToBigEndian(_rdata[i].M3);
+ rd.append((const char*)&(_rdata[i]), 11); //sizeof(RobotData);
}
unsigned char checksum=0;
diff --git a/src/output/wpacket.h b/src/output/wpacket.h
index 236d775..c0be0d0 100644
--- a/src/output/wpacket.h
+++ b/src/output/wpacket.h
@@ -29,16 +29,6 @@ struct SendPacketHeader
struct RobotData
{
unsigned char RID; // robot id
- signed short int Vx_sp;
- signed short int Vy_sp;
- signed short int Wr_sp;
- signed short int Vx;
- signed short int Vy;
- signed short int Wr;
- signed short int alpha;
- unsigned char KICK; // kick options
- unsigned char CHIP; // CHIP & SPIN #SCCCCCCC
- unsigned char SPIN;
signed short int M0; // motor 1
signed short int M1; // motor 2
signed short int M2; // motor 3
@@ -48,16 +38,12 @@ struct RobotData
RobotData() :
RID(0xFF),
- Vx_sp(0),
- Vy_sp(0),
- Wr_sp(0),
- Vx(0),
- Vy(0),
- Wr(0),
- alpha(0),
- KICK(0),
- CHIP(0),
- SPIN(0)
+ M0(0),
+ M1(0),
+ M2(0),
+ M3(0),
+ KCK(0),
+ CHP(0)
{ }
};
#pragma pack(pop) /* restore original alignment from stack */
diff --git a/src/proto/Ball_message.pb.cc b/src/proto/Ball_message.pb.cc
index 03079e5..2e96c91 100644
--- a/src/proto/Ball_message.pb.cc
+++ b/src/proto/Ball_message.pb.cc
@@ -7,6 +7,7 @@
#include
#include
+#include
#include
#include
#include
@@ -15,81 +16,106 @@
#include
#include
// @@protoc_insertion_point(includes)
+class Ball_messageDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed {};
+Ball_messageDefaultTypeInternal _Ball_message_default_instance_;
namespace {
-const ::google::protobuf::Descriptor* Ball_message_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- Ball_message_reflection_ = NULL;
+::google::protobuf::Metadata file_level_metadata[1];
} // namespace
-void protobuf_AssignDesc_Ball_5fmessage_2eproto() {
- protobuf_AddDesc_Ball_5fmessage_2eproto();
- const ::google::protobuf::FileDescriptor* file =
- ::google::protobuf::DescriptorPool::generated_pool()->FindFileByName(
- "Ball_message.proto");
- GOOGLE_CHECK(file != NULL);
- Ball_message_descriptor_ = file->message_type(0);
- static const int Ball_message_offsets_[3] = {
+const ::google::protobuf::uint32* protobuf_Offsets_Ball_5fmessage_2eproto() GOOGLE_ATTRIBUTE_COLD;
+const ::google::protobuf::uint32* protobuf_Offsets_Ball_5fmessage_2eproto() {
+ static const ::google::protobuf::uint32 offsets[] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Ball_message, _has_bits_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Ball_message, _internal_metadata_),
+ ~0u, // no _extensions_
+ ~0u, // no _oneof_case_
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Ball_message, isvalid_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Ball_message, position_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Ball_message, velocity_),
+ 2,
+ 0,
+ 1,
};
- Ball_message_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- Ball_message_descriptor_,
- Ball_message::default_instance_,
- Ball_message_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Ball_message, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Ball_message, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(Ball_message));
+ return offsets;
}
+static const ::google::protobuf::internal::MigrationSchema schemas[] = {
+ { 0, 7, sizeof(Ball_message)},
+};
+
+static const ::google::protobuf::internal::DefaultInstanceData file_default_instances[] = {
+ {reinterpret_cast(&_Ball_message_default_instance_), NULL},
+};
+
namespace {
-GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AssignDescriptors_once_);
-inline void protobuf_AssignDescriptorsOnce() {
- ::google::protobuf::GoogleOnceInit(&protobuf_AssignDescriptors_once_,
- &protobuf_AssignDesc_Ball_5fmessage_2eproto);
+void protobuf_AssignDescriptors() {
+ protobuf_AddDesc_Ball_5fmessage_2eproto();
+ ::google::protobuf::MessageFactory* factory = NULL;
+ AssignDescriptors(
+ "Ball_message.proto", schemas, file_default_instances, protobuf_Offsets_Ball_5fmessage_2eproto(), factory,
+ file_level_metadata, NULL, NULL);
}
+void protobuf_AssignDescriptorsOnce() {
+ static GOOGLE_PROTOBUF_DECLARE_ONCE(once);
+ ::google::protobuf::GoogleOnceInit(&once, &protobuf_AssignDescriptors);
+}
+
+void protobuf_RegisterTypes(const ::std::string&) GOOGLE_ATTRIBUTE_COLD;
void protobuf_RegisterTypes(const ::std::string&) {
protobuf_AssignDescriptorsOnce();
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- Ball_message_descriptor_, &Ball_message::default_instance());
+ ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 1);
}
} // namespace
void protobuf_ShutdownFile_Ball_5fmessage_2eproto() {
- delete Ball_message::default_instance_;
- delete Ball_message_reflection_;
+ _Ball_message_default_instance_.Shutdown();
+ delete file_level_metadata[0].reflection;
}
-void protobuf_AddDesc_Ball_5fmessage_2eproto() {
- static bool already_here = false;
- if (already_here) return;
- already_here = true;
+void protobuf_InitDefaults_Ball_5fmessage_2eproto_impl() {
GOOGLE_PROTOBUF_VERIFY_VERSION;
- ::protobuf_AddDesc_position_5fmessage_2eproto();
+ ::protobuf_InitDefaults_position_5fmessage_2eproto();
+ ::google::protobuf::internal::InitProtobufDefaults();
+ _Ball_message_default_instance_.DefaultConstruct();
+ _Ball_message_default_instance_.get_mutable()->position_ = const_cast< ::position_message*>(
+ ::position_message::internal_default_instance());
+ _Ball_message_default_instance_.get_mutable()->velocity_ = const_cast< ::position_message*>(
+ ::position_message::internal_default_instance());
+}
+
+void protobuf_InitDefaults_Ball_5fmessage_2eproto() {
+ static GOOGLE_PROTOBUF_DECLARE_ONCE(once);
+ ::google::protobuf::GoogleOnceInit(&once, &protobuf_InitDefaults_Ball_5fmessage_2eproto_impl);
+}
+void protobuf_AddDesc_Ball_5fmessage_2eproto_impl() {
+ protobuf_InitDefaults_Ball_5fmessage_2eproto();
+ static const char descriptor[] = {
+ "\n\022Ball_message.proto\032\026position_message.p"
+ "roto\"i\n\014Ball_message\022\017\n\007isValid\030\001 \002(\010\022#\n"
+ "\010position\030\002 \002(\0132\021.position_message\022#\n\010ve"
+ "locity\030\003 \002(\0132\021.position_message"
+ };
::google::protobuf::DescriptorPool::InternalAddGeneratedFile(
- "\n\022Ball_message.proto\032\026position_message.p"
- "roto\"i\n\014Ball_message\022\017\n\007isValid\030\001 \002(\010\022#\n"
- "\010position\030\002 \002(\0132\021.position_message\022#\n\010ve"
- "locity\030\003 \002(\0132\021.position_message", 151);
+ descriptor, 151);
::google::protobuf::MessageFactory::InternalRegisterGeneratedFile(
"Ball_message.proto", &protobuf_RegisterTypes);
- Ball_message::default_instance_ = new Ball_message();
- Ball_message::default_instance_->InitAsDefaultInstance();
+ ::protobuf_AddDesc_position_5fmessage_2eproto();
::google::protobuf::internal::OnShutdown(&protobuf_ShutdownFile_Ball_5fmessage_2eproto);
}
+GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AddDesc_Ball_5fmessage_2eproto_once_);
+void protobuf_AddDesc_Ball_5fmessage_2eproto() {
+ ::google::protobuf::GoogleOnceInit(&protobuf_AddDesc_Ball_5fmessage_2eproto_once_,
+ &protobuf_AddDesc_Ball_5fmessage_2eproto_impl);
+}
// Force AddDescriptors() to be called at static initialization time.
struct StaticDescriptorInitializer_Ball_5fmessage_2eproto {
StaticDescriptorInitializer_Ball_5fmessage_2eproto() {
@@ -99,43 +125,56 @@ struct StaticDescriptorInitializer_Ball_5fmessage_2eproto {
// ===================================================================
-#ifndef _MSC_VER
+#if !defined(_MSC_VER) || _MSC_VER >= 1900
const int Ball_message::kIsValidFieldNumber;
const int Ball_message::kPositionFieldNumber;
const int Ball_message::kVelocityFieldNumber;
-#endif // !_MSC_VER
+#endif // !defined(_MSC_VER) || _MSC_VER >= 1900
Ball_message::Ball_message()
- : ::google::protobuf::Message() {
+ : ::google::protobuf::Message(), _internal_metadata_(NULL) {
+ if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) {
+ protobuf_InitDefaults_Ball_5fmessage_2eproto();
+ }
SharedCtor();
+ // @@protoc_insertion_point(constructor:Ball_message)
}
-
-void Ball_message::InitAsDefaultInstance() {
- position_ = const_cast< ::position_message*>(&::position_message::default_instance());
- velocity_ = const_cast< ::position_message*>(&::position_message::default_instance());
-}
-
Ball_message::Ball_message(const Ball_message& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
+ : ::google::protobuf::Message(),
+ _internal_metadata_(NULL),
+ _has_bits_(from._has_bits_),
+ _cached_size_(0) {
+ _internal_metadata_.MergeFrom(from._internal_metadata_);
+ if (from.has_position()) {
+ position_ = new ::position_message(*from.position_);
+ } else {
+ position_ = NULL;
+ }
+ if (from.has_velocity()) {
+ velocity_ = new ::position_message(*from.velocity_);
+ } else {
+ velocity_ = NULL;
+ }
+ isvalid_ = from.isvalid_;
+ // @@protoc_insertion_point(copy_constructor:Ball_message)
}
void Ball_message::SharedCtor() {
_cached_size_ = 0;
- isvalid_ = false;
- position_ = NULL;
- velocity_ = NULL;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ ::memset(&position_, 0, reinterpret_cast(&isvalid_) -
+ reinterpret_cast(&position_) + sizeof(isvalid_));
}
Ball_message::~Ball_message() {
+ // @@protoc_insertion_point(destructor:Ball_message)
SharedDtor();
}
void Ball_message::SharedDtor() {
- if (this != default_instance_) {
+ if (this != internal_default_instance()) {
delete position_;
+ }
+ if (this != internal_default_instance()) {
delete velocity_;
}
}
@@ -147,88 +186,90 @@ void Ball_message::SetCachedSize(int size) const {
}
const ::google::protobuf::Descriptor* Ball_message::descriptor() {
protobuf_AssignDescriptorsOnce();
- return Ball_message_descriptor_;
+ return file_level_metadata[0].descriptor;
}
const Ball_message& Ball_message::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_Ball_5fmessage_2eproto();
- return *default_instance_;
+ protobuf_InitDefaults_Ball_5fmessage_2eproto();
+ return *internal_default_instance();
}
-Ball_message* Ball_message::default_instance_ = NULL;
-
-Ball_message* Ball_message::New() const {
- return new Ball_message;
+Ball_message* Ball_message::New(::google::protobuf::Arena* arena) const {
+ Ball_message* n = new Ball_message;
+ if (arena != NULL) {
+ arena->Own(n);
+ }
+ return n;
}
void Ball_message::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- isvalid_ = false;
+// @@protoc_insertion_point(message_clear_start:Ball_message)
+ if (_has_bits_[0 / 32] & 3u) {
if (has_position()) {
- if (position_ != NULL) position_->::position_message::Clear();
+ GOOGLE_DCHECK(position_ != NULL);
+ position_->::position_message::Clear();
}
if (has_velocity()) {
- if (velocity_ != NULL) velocity_->::position_message::Clear();
+ GOOGLE_DCHECK(velocity_ != NULL);
+ velocity_->::position_message::Clear();
}
}
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
+ isvalid_ = false;
+ _has_bits_.Clear();
+ _internal_metadata_.Clear();
}
bool Ball_message::MergePartialFromCodedStream(
::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure
::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
+ // @@protoc_insertion_point(parse_start:Ball_message)
+ for (;;) {
+ ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u);
+ tag = p.first;
+ if (!p.second) goto handle_unusual;
switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
// required bool isValid = 1;
case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ if (tag == 8u) {
+ set_has_isvalid();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>(
input, &isvalid_)));
- set_has_isvalid();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(18)) goto parse_position;
break;
}
// required .position_message position = 2;
case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_position:
+ if (tag == 18u) {
DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
input, mutable_position()));
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(26)) goto parse_velocity;
break;
}
// required .position_message velocity = 3;
case 3: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_velocity:
+ if (tag == 26u) {
DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
input, mutable_velocity()));
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectAtEnd()) return true;
break;
}
default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ handle_unusual:
+ if (tag == 0 ||
+ ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
+ goto success;
}
DO_(::google::protobuf::internal::WireFormat::SkipField(
input, tag, mutable_unknown_fields()));
@@ -236,12 +277,18 @@ bool Ball_message::MergePartialFromCodedStream(
}
}
}
+success:
+ // @@protoc_insertion_point(parse_success:Ball_message)
return true;
+failure:
+ // @@protoc_insertion_point(parse_failure:Ball_message)
+ return false;
#undef DO_
}
void Ball_message::SerializeWithCachedSizes(
::google::protobuf::io::CodedOutputStream* output) const {
+ // @@protoc_insertion_point(serialize_start:Ball_message)
// required bool isValid = 1;
if (has_isvalid()) {
::google::protobuf::internal::WireFormatLite::WriteBool(1, this->isvalid(), output);
@@ -250,23 +297,26 @@ void Ball_message::SerializeWithCachedSizes(
// required .position_message position = 2;
if (has_position()) {
::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 2, this->position(), output);
+ 2, *this->position_, output);
}
// required .position_message velocity = 3;
if (has_velocity()) {
::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 3, this->velocity(), output);
+ 3, *this->velocity_, output);
}
- if (!unknown_fields().empty()) {
+ if (_internal_metadata_.have_unknown_fields()) {
::google::protobuf::internal::WireFormat::SerializeUnknownFields(
unknown_fields(), output);
}
+ // @@protoc_insertion_point(serialize_end:Ball_message)
}
-::google::protobuf::uint8* Ball_message::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
+::google::protobuf::uint8* Ball_message::InternalSerializeWithCachedSizesToArray(
+ bool deterministic, ::google::protobuf::uint8* target) const {
+ (void)deterministic; // Unused
+ // @@protoc_insertion_point(serialize_to_array_start:Ball_message)
// required bool isValid = 1;
if (has_isvalid()) {
target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->isvalid(), target);
@@ -275,94 +325,124 @@ ::google::protobuf::uint8* Ball_message::SerializeWithCachedSizesToArray(
// required .position_message position = 2;
if (has_position()) {
target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 2, this->position(), target);
+ InternalWriteMessageNoVirtualToArray(
+ 2, *this->position_, false, target);
}
// required .position_message velocity = 3;
if (has_velocity()) {
target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 3, this->velocity(), target);
+ InternalWriteMessageNoVirtualToArray(
+ 3, *this->velocity_, false, target);
}
- if (!unknown_fields().empty()) {
+ if (_internal_metadata_.have_unknown_fields()) {
target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
unknown_fields(), target);
}
+ // @@protoc_insertion_point(serialize_to_array_end:Ball_message)
return target;
}
-int Ball_message::ByteSize() const {
- int total_size = 0;
-
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- // required bool isValid = 1;
- if (has_isvalid()) {
- total_size += 1 + 1;
- }
+size_t Ball_message::RequiredFieldsByteSizeFallback() const {
+// @@protoc_insertion_point(required_fields_byte_size_fallback_start:Ball_message)
+ size_t total_size = 0;
+ if (has_position()) {
// required .position_message position = 2;
- if (has_position()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->position());
- }
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ *this->position_);
+ }
+ if (has_velocity()) {
// required .position_message velocity = 3;
- if (has_velocity()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->velocity());
- }
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ *this->velocity_);
+ }
+ if (has_isvalid()) {
+ // required bool isValid = 1;
+ total_size += 1 + 1;
}
- if (!unknown_fields().empty()) {
+
+ return total_size;
+}
+size_t Ball_message::ByteSizeLong() const {
+// @@protoc_insertion_point(message_byte_size_start:Ball_message)
+ size_t total_size = 0;
+
+ if (_internal_metadata_.have_unknown_fields()) {
total_size +=
::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
unknown_fields());
}
+ if (((_has_bits_[0] & 0x00000007) ^ 0x00000007) == 0) { // All required fields are present.
+ // required .position_message position = 2;
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ *this->position_);
+
+ // required .position_message velocity = 3;
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ *this->velocity_);
+
+ // required bool isValid = 1;
+ total_size += 1 + 1;
+
+ } else {
+ total_size += RequiredFieldsByteSizeFallback();
+ }
+ int cached_size = ::google::protobuf::internal::ToCachedSize(total_size);
GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
+ _cached_size_ = cached_size;
GOOGLE_SAFE_CONCURRENT_WRITES_END();
return total_size;
}
void Ball_message::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
+// @@protoc_insertion_point(generalized_merge_from_start:Ball_message)
+ GOOGLE_DCHECK_NE(&from, this);
const Ball_message* source =
- ::google::protobuf::internal::dynamic_cast_if_available(
- &from);
+ ::google::protobuf::internal::DynamicCastToGenerated(
+ &from);
if (source == NULL) {
+ // @@protoc_insertion_point(generalized_merge_from_cast_fail:Ball_message)
::google::protobuf::internal::ReflectionOps::Merge(from, this);
} else {
+ // @@protoc_insertion_point(generalized_merge_from_cast_success:Ball_message)
MergeFrom(*source);
}
}
void Ball_message::MergeFrom(const Ball_message& from) {
- GOOGLE_CHECK_NE(&from, this);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_isvalid()) {
- set_isvalid(from.isvalid());
- }
+// @@protoc_insertion_point(class_specific_merge_from_start:Ball_message)
+ GOOGLE_DCHECK_NE(&from, this);
+ _internal_metadata_.MergeFrom(from._internal_metadata_);
+ if (from._has_bits_[0 / 32] & 7u) {
if (from.has_position()) {
mutable_position()->::position_message::MergeFrom(from.position());
}
if (from.has_velocity()) {
mutable_velocity()->::position_message::MergeFrom(from.velocity());
}
+ if (from.has_isvalid()) {
+ set_isvalid(from.isvalid());
+ }
}
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
}
void Ball_message::CopyFrom(const ::google::protobuf::Message& from) {
+// @@protoc_insertion_point(generalized_copy_from_start:Ball_message)
if (&from == this) return;
Clear();
MergeFrom(from);
}
void Ball_message::CopyFrom(const Ball_message& from) {
+// @@protoc_insertion_point(class_specific_copy_from_start:Ball_message)
if (&from == this) return;
Clear();
MergeFrom(from);
@@ -370,35 +450,151 @@ void Ball_message::CopyFrom(const Ball_message& from) {
bool Ball_message::IsInitialized() const {
if ((_has_bits_[0] & 0x00000007) != 0x00000007) return false;
-
if (has_position()) {
- if (!this->position().IsInitialized()) return false;
+ if (!this->position_->IsInitialized()) return false;
}
if (has_velocity()) {
- if (!this->velocity().IsInitialized()) return false;
+ if (!this->velocity_->IsInitialized()) return false;
}
return true;
}
void Ball_message::Swap(Ball_message* other) {
- if (other != this) {
- std::swap(isvalid_, other->isvalid_);
- std::swap(position_, other->position_);
- std::swap(velocity_, other->velocity_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
+ if (other == this) return;
+ InternalSwap(other);
+}
+void Ball_message::InternalSwap(Ball_message* other) {
+ std::swap(position_, other->position_);
+ std::swap(velocity_, other->velocity_);
+ std::swap(isvalid_, other->isvalid_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _internal_metadata_.Swap(&other->_internal_metadata_);
+ std::swap(_cached_size_, other->_cached_size_);
}
::google::protobuf::Metadata Ball_message::GetMetadata() const {
protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = Ball_message_descriptor_;
- metadata.reflection = Ball_message_reflection_;
- return metadata;
+ return file_level_metadata[0];
+}
+
+#if PROTOBUF_INLINE_NOT_IN_HEADERS
+// Ball_message
+
+// required bool isValid = 1;
+bool Ball_message::has_isvalid() const {
+ return (_has_bits_[0] & 0x00000004u) != 0;
+}
+void Ball_message::set_has_isvalid() {
+ _has_bits_[0] |= 0x00000004u;
+}
+void Ball_message::clear_has_isvalid() {
+ _has_bits_[0] &= ~0x00000004u;
+}
+void Ball_message::clear_isvalid() {
+ isvalid_ = false;
+ clear_has_isvalid();
+}
+bool Ball_message::isvalid() const {
+ // @@protoc_insertion_point(field_get:Ball_message.isValid)
+ return isvalid_;
+}
+void Ball_message::set_isvalid(bool value) {
+ set_has_isvalid();
+ isvalid_ = value;
+ // @@protoc_insertion_point(field_set:Ball_message.isValid)
+}
+
+// required .position_message position = 2;
+bool Ball_message::has_position() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+void Ball_message::set_has_position() {
+ _has_bits_[0] |= 0x00000001u;
+}
+void Ball_message::clear_has_position() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+void Ball_message::clear_position() {
+ if (position_ != NULL) position_->::position_message::Clear();
+ clear_has_position();
+}
+const ::position_message& Ball_message::position() const {
+ // @@protoc_insertion_point(field_get:Ball_message.position)
+ return position_ != NULL ? *position_
+ : *::position_message::internal_default_instance();
+}
+::position_message* Ball_message::mutable_position() {
+ set_has_position();
+ if (position_ == NULL) {
+ position_ = new ::position_message;
+ }
+ // @@protoc_insertion_point(field_mutable:Ball_message.position)
+ return position_;
+}
+::position_message* Ball_message::release_position() {
+ // @@protoc_insertion_point(field_release:Ball_message.position)
+ clear_has_position();
+ ::position_message* temp = position_;
+ position_ = NULL;
+ return temp;
+}
+void Ball_message::set_allocated_position(::position_message* position) {
+ delete position_;
+ position_ = position;
+ if (position) {
+ set_has_position();
+ } else {
+ clear_has_position();
+ }
+ // @@protoc_insertion_point(field_set_allocated:Ball_message.position)
+}
+
+// required .position_message velocity = 3;
+bool Ball_message::has_velocity() const {
+ return (_has_bits_[0] & 0x00000002u) != 0;
+}
+void Ball_message::set_has_velocity() {
+ _has_bits_[0] |= 0x00000002u;
+}
+void Ball_message::clear_has_velocity() {
+ _has_bits_[0] &= ~0x00000002u;
+}
+void Ball_message::clear_velocity() {
+ if (velocity_ != NULL) velocity_->::position_message::Clear();
+ clear_has_velocity();
+}
+const ::position_message& Ball_message::velocity() const {
+ // @@protoc_insertion_point(field_get:Ball_message.velocity)
+ return velocity_ != NULL ? *velocity_
+ : *::position_message::internal_default_instance();
+}
+::position_message* Ball_message::mutable_velocity() {
+ set_has_velocity();
+ if (velocity_ == NULL) {
+ velocity_ = new ::position_message;
+ }
+ // @@protoc_insertion_point(field_mutable:Ball_message.velocity)
+ return velocity_;
+}
+::position_message* Ball_message::release_velocity() {
+ // @@protoc_insertion_point(field_release:Ball_message.velocity)
+ clear_has_velocity();
+ ::position_message* temp = velocity_;
+ velocity_ = NULL;
+ return temp;
+}
+void Ball_message::set_allocated_velocity(::position_message* velocity) {
+ delete velocity_;
+ velocity_ = velocity;
+ if (velocity) {
+ set_has_velocity();
+ } else {
+ clear_has_velocity();
+ }
+ // @@protoc_insertion_point(field_set_allocated:Ball_message.velocity)
}
+#endif // PROTOBUF_INLINE_NOT_IN_HEADERS
// @@protoc_insertion_point(namespace_scope)
diff --git a/src/proto/Ball_message.pb.h b/src/proto/Ball_message.pb.h
index 059e7d0..371acec 100644
--- a/src/proto/Ball_message.pb.h
+++ b/src/proto/Ball_message.pb.h
@@ -8,35 +8,41 @@
#include
-#if GOOGLE_PROTOBUF_VERSION < 2005000
+#if GOOGLE_PROTOBUF_VERSION < 3001000
#error This file was generated by a newer version of protoc which is
#error incompatible with your Protocol Buffer headers. Please update
#error your headers.
#endif
-#if 2005000 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION
+#if 3001000 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION
#error This file was generated by an older version of protoc which is
#error incompatible with your Protocol Buffer headers. Please
#error regenerate this file with a newer version of protoc.
#endif
+#include
+#include
#include
+#include
#include
-#include
-#include
+#include // IWYU pragma: export
+#include // IWYU pragma: export
#include
#include "position_message.pb.h"
// @@protoc_insertion_point(includes)
+class Ball_message;
+class Ball_messageDefaultTypeInternal;
+extern Ball_messageDefaultTypeInternal _Ball_message_default_instance_;
+class position_message;
+class position_messageDefaultTypeInternal;
+extern position_messageDefaultTypeInternal _position_message_default_instance_;
// Internal implementation detail -- do not call these.
-void protobuf_AddDesc_Ball_5fmessage_2eproto();
-void protobuf_AssignDesc_Ball_5fmessage_2eproto();
-void protobuf_ShutdownFile_Ball_5fmessage_2eproto();
-
-class Ball_message;
+void protobuf_AddDesc_Ball_5fmessage_2eproto();
+void protobuf_InitDefaults_Ball_5fmessage_2eproto();
// ===================================================================
-class Ball_message : public ::google::protobuf::Message {
+class Ball_message : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:Ball_message) */ {
public:
Ball_message();
virtual ~Ball_message();
@@ -49,149 +55,177 @@ class Ball_message : public ::google::protobuf::Message {
}
inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
+ return _internal_metadata_.unknown_fields();
}
inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
+ return _internal_metadata_.mutable_unknown_fields();
}
static const ::google::protobuf::Descriptor* descriptor();
static const Ball_message& default_instance();
+ static inline const Ball_message* internal_default_instance() {
+ return reinterpret_cast(
+ &_Ball_message_default_instance_);
+ }
+
void Swap(Ball_message* other);
// implements Message ----------------------------------------------
- Ball_message* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
+ inline Ball_message* New() const PROTOBUF_FINAL { return New(NULL); }
+
+ Ball_message* New(::google::protobuf::Arena* arena) const PROTOBUF_FINAL;
+ void CopyFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL;
+ void MergeFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL;
void CopyFrom(const Ball_message& from);
void MergeFrom(const Ball_message& from);
- void Clear();
- bool IsInitialized() const;
+ void Clear() PROTOBUF_FINAL;
+ bool IsInitialized() const PROTOBUF_FINAL;
- int ByteSize() const;
+ size_t ByteSizeLong() const PROTOBUF_FINAL;
bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
+ ::google::protobuf::io::CodedInputStream* input) PROTOBUF_FINAL;
void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
+ ::google::protobuf::io::CodedOutputStream* output) const PROTOBUF_FINAL;
+ ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray(
+ bool deterministic, ::google::protobuf::uint8* target) const PROTOBUF_FINAL;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output)
+ const PROTOBUF_FINAL {
+ return InternalSerializeWithCachedSizesToArray(false, output);
+ }
+ int GetCachedSize() const PROTOBUF_FINAL { return _cached_size_; }
private:
void SharedCtor();
void SharedDtor();
- void SetCachedSize(int size) const;
+ void SetCachedSize(int size) const PROTOBUF_FINAL;
+ void InternalSwap(Ball_message* other);
+ private:
+ inline ::google::protobuf::Arena* GetArenaNoVirtual() const {
+ return NULL;
+ }
+ inline void* MaybeArenaPtr() const {
+ return NULL;
+ }
public:
- ::google::protobuf::Metadata GetMetadata() const;
+ ::google::protobuf::Metadata GetMetadata() const PROTOBUF_FINAL;
// nested types ----------------------------------------------------
// accessors -------------------------------------------------------
// required bool isValid = 1;
- inline bool has_isvalid() const;
- inline void clear_isvalid();
+ bool has_isvalid() const;
+ void clear_isvalid();
static const int kIsValidFieldNumber = 1;
- inline bool isvalid() const;
- inline void set_isvalid(bool value);
+ bool isvalid() const;
+ void set_isvalid(bool value);
// required .position_message position = 2;
- inline bool has_position() const;
- inline void clear_position();
+ bool has_position() const;
+ void clear_position();
static const int kPositionFieldNumber = 2;
- inline const ::position_message& position() const;
- inline ::position_message* mutable_position();
- inline ::position_message* release_position();
- inline void set_allocated_position(::position_message* position);
+ const ::position_message& position() const;
+ ::position_message* mutable_position();
+ ::position_message* release_position();
+ void set_allocated_position(::position_message* position);
// required .position_message velocity = 3;
- inline bool has_velocity() const;
- inline void clear_velocity();
+ bool has_velocity() const;
+ void clear_velocity();
static const int kVelocityFieldNumber = 3;
- inline const ::position_message& velocity() const;
- inline ::position_message* mutable_velocity();
- inline ::position_message* release_velocity();
- inline void set_allocated_velocity(::position_message* velocity);
+ const ::position_message& velocity() const;
+ ::position_message* mutable_velocity();
+ ::position_message* release_velocity();
+ void set_allocated_velocity(::position_message* velocity);
// @@protoc_insertion_point(class_scope:Ball_message)
private:
- inline void set_has_isvalid();
- inline void clear_has_isvalid();
- inline void set_has_position();
- inline void clear_has_position();
- inline void set_has_velocity();
- inline void clear_has_velocity();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
+ void set_has_isvalid();
+ void clear_has_isvalid();
+ void set_has_position();
+ void clear_has_position();
+ void set_has_velocity();
+ void clear_has_velocity();
+
+ // helper for ByteSizeLong()
+ size_t RequiredFieldsByteSizeFallback() const;
+
+ ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_;
+ ::google::protobuf::internal::HasBits<1> _has_bits_;
+ mutable int _cached_size_;
::position_message* position_;
::position_message* velocity_;
bool isvalid_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(3 + 31) / 32];
-
- friend void protobuf_AddDesc_Ball_5fmessage_2eproto();
- friend void protobuf_AssignDesc_Ball_5fmessage_2eproto();
+ friend void protobuf_InitDefaults_Ball_5fmessage_2eproto_impl();
+ friend void protobuf_AddDesc_Ball_5fmessage_2eproto_impl();
+ friend const ::google::protobuf::uint32* protobuf_Offsets_Ball_5fmessage_2eproto();
friend void protobuf_ShutdownFile_Ball_5fmessage_2eproto();
- void InitAsDefaultInstance();
- static Ball_message* default_instance_;
};
// ===================================================================
// ===================================================================
+#if !PROTOBUF_INLINE_NOT_IN_HEADERS
// Ball_message
// required bool isValid = 1;
inline bool Ball_message::has_isvalid() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
+ return (_has_bits_[0] & 0x00000004u) != 0;
}
inline void Ball_message::set_has_isvalid() {
- _has_bits_[0] |= 0x00000001u;
+ _has_bits_[0] |= 0x00000004u;
}
inline void Ball_message::clear_has_isvalid() {
- _has_bits_[0] &= ~0x00000001u;
+ _has_bits_[0] &= ~0x00000004u;
}
inline void Ball_message::clear_isvalid() {
isvalid_ = false;
clear_has_isvalid();
}
inline bool Ball_message::isvalid() const {
+ // @@protoc_insertion_point(field_get:Ball_message.isValid)
return isvalid_;
}
inline void Ball_message::set_isvalid(bool value) {
set_has_isvalid();
isvalid_ = value;
+ // @@protoc_insertion_point(field_set:Ball_message.isValid)
}
// required .position_message position = 2;
inline bool Ball_message::has_position() const {
- return (_has_bits_[0] & 0x00000002u) != 0;
+ return (_has_bits_[0] & 0x00000001u) != 0;
}
inline void Ball_message::set_has_position() {
- _has_bits_[0] |= 0x00000002u;
+ _has_bits_[0] |= 0x00000001u;
}
inline void Ball_message::clear_has_position() {
- _has_bits_[0] &= ~0x00000002u;
+ _has_bits_[0] &= ~0x00000001u;
}
inline void Ball_message::clear_position() {
if (position_ != NULL) position_->::position_message::Clear();
clear_has_position();
}
inline const ::position_message& Ball_message::position() const {
- return position_ != NULL ? *position_ : *default_instance_->position_;
+ // @@protoc_insertion_point(field_get:Ball_message.position)
+ return position_ != NULL ? *position_
+ : *::position_message::internal_default_instance();
}
inline ::position_message* Ball_message::mutable_position() {
set_has_position();
- if (position_ == NULL) position_ = new ::position_message;
+ if (position_ == NULL) {
+ position_ = new ::position_message;
+ }
+ // @@protoc_insertion_point(field_mutable:Ball_message.position)
return position_;
}
inline ::position_message* Ball_message::release_position() {
+ // @@protoc_insertion_point(field_release:Ball_message.position)
clear_has_position();
::position_message* temp = position_;
position_ = NULL;
@@ -205,31 +239,38 @@ inline void Ball_message::set_allocated_position(::position_message* position) {
} else {
clear_has_position();
}
+ // @@protoc_insertion_point(field_set_allocated:Ball_message.position)
}
// required .position_message velocity = 3;
inline bool Ball_message::has_velocity() const {
- return (_has_bits_[0] & 0x00000004u) != 0;
+ return (_has_bits_[0] & 0x00000002u) != 0;
}
inline void Ball_message::set_has_velocity() {
- _has_bits_[0] |= 0x00000004u;
+ _has_bits_[0] |= 0x00000002u;
}
inline void Ball_message::clear_has_velocity() {
- _has_bits_[0] &= ~0x00000004u;
+ _has_bits_[0] &= ~0x00000002u;
}
inline void Ball_message::clear_velocity() {
if (velocity_ != NULL) velocity_->::position_message::Clear();
clear_has_velocity();
}
inline const ::position_message& Ball_message::velocity() const {
- return velocity_ != NULL ? *velocity_ : *default_instance_->velocity_;
+ // @@protoc_insertion_point(field_get:Ball_message.velocity)
+ return velocity_ != NULL ? *velocity_
+ : *::position_message::internal_default_instance();
}
inline ::position_message* Ball_message::mutable_velocity() {
set_has_velocity();
- if (velocity_ == NULL) velocity_ = new ::position_message;
+ if (velocity_ == NULL) {
+ velocity_ = new ::position_message;
+ }
+ // @@protoc_insertion_point(field_mutable:Ball_message.velocity)
return velocity_;
}
inline ::position_message* Ball_message::release_velocity() {
+ // @@protoc_insertion_point(field_release:Ball_message.velocity)
clear_has_velocity();
::position_message* temp = velocity_;
velocity_ = NULL;
@@ -243,19 +284,13 @@ inline void Ball_message::set_allocated_velocity(::position_message* velocity) {
} else {
clear_has_velocity();
}
+ // @@protoc_insertion_point(field_set_allocated:Ball_message.velocity)
}
+#endif // !PROTOBUF_INLINE_NOT_IN_HEADERS
// @@protoc_insertion_point(namespace_scope)
-#ifndef SWIG
-namespace google {
-namespace protobuf {
-
-
-} // namespace google
-} // namespace protobuf
-#endif // SWIG
// @@protoc_insertion_point(global_scope)
diff --git a/src/proto/RobotCommand_message.pb.cc b/src/proto/RobotCommand_message.pb.cc
index 5cbc3b2..76323cb 100644
--- a/src/proto/RobotCommand_message.pb.cc
+++ b/src/proto/RobotCommand_message.pb.cc
@@ -7,6 +7,7 @@
#include
#include
+#include
#include
#include
#include
@@ -15,24 +16,23 @@
#include
#include
// @@protoc_insertion_point(includes)
+class RobotCommand_messageDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed {};
+RobotCommand_messageDefaultTypeInternal _RobotCommand_message_default_instance_;
namespace {
-const ::google::protobuf::Descriptor* RobotCommand_message_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- RobotCommand_message_reflection_ = NULL;
+::google::protobuf::Metadata file_level_metadata[1];
} // namespace
-void protobuf_AssignDesc_RobotCommand_5fmessage_2eproto() {
- protobuf_AddDesc_RobotCommand_5fmessage_2eproto();
- const ::google::protobuf::FileDescriptor* file =
- ::google::protobuf::DescriptorPool::generated_pool()->FindFileByName(
- "RobotCommand_message.proto");
- GOOGLE_CHECK(file != NULL);
- RobotCommand_message_descriptor_ = file->message_type(0);
- static const int RobotCommand_message_offsets_[8] = {
+const ::google::protobuf::uint32* protobuf_Offsets_RobotCommand_5fmessage_2eproto() GOOGLE_ATTRIBUTE_COLD;
+const ::google::protobuf::uint32* protobuf_Offsets_RobotCommand_5fmessage_2eproto() {
+ static const ::google::protobuf::uint32 offsets[] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RobotCommand_message, _has_bits_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RobotCommand_message, _internal_metadata_),
+ ~0u, // no _extensions_
+ ~0u, // no _oneof_case_
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RobotCommand_message, fin_pos_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RobotCommand_message, fin_vel_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RobotCommand_message, maxspeed_),
@@ -41,63 +41,94 @@ void protobuf_AssignDesc_RobotCommand_5fmessage_2eproto() {
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RobotCommand_message, usenav_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RobotCommand_message, isballobs_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RobotCommand_message, iskickobs_),
+ 0,
+ 1,
+ 2,
+ 3,
+ 4,
+ 5,
+ 6,
+ 7,
};
- RobotCommand_message_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- RobotCommand_message_descriptor_,
- RobotCommand_message::default_instance_,
- RobotCommand_message_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RobotCommand_message, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(RobotCommand_message, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(RobotCommand_message));
+ return offsets;
}
+static const ::google::protobuf::internal::MigrationSchema schemas[] = {
+ { 0, 12, sizeof(RobotCommand_message)},
+};
+
+static const ::google::protobuf::internal::DefaultInstanceData file_default_instances[] = {
+ {reinterpret_cast(&_RobotCommand_message_default_instance_), NULL},
+};
+
namespace {
-GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AssignDescriptors_once_);
-inline void protobuf_AssignDescriptorsOnce() {
- ::google::protobuf::GoogleOnceInit(&protobuf_AssignDescriptors_once_,
- &protobuf_AssignDesc_RobotCommand_5fmessage_2eproto);
+void protobuf_AssignDescriptors() {
+ protobuf_AddDesc_RobotCommand_5fmessage_2eproto();
+ ::google::protobuf::MessageFactory* factory = NULL;
+ AssignDescriptors(
+ "RobotCommand_message.proto", schemas, file_default_instances, protobuf_Offsets_RobotCommand_5fmessage_2eproto(), factory,
+ file_level_metadata, NULL, NULL);
+}
+
+void protobuf_AssignDescriptorsOnce() {
+ static GOOGLE_PROTOBUF_DECLARE_ONCE(once);
+ ::google::protobuf::GoogleOnceInit(&once, &protobuf_AssignDescriptors);
}
+void protobuf_RegisterTypes(const ::std::string&) GOOGLE_ATTRIBUTE_COLD;
void protobuf_RegisterTypes(const ::std::string&) {
protobuf_AssignDescriptorsOnce();
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- RobotCommand_message_descriptor_, &RobotCommand_message::default_instance());
+ ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 1);
}
} // namespace
void protobuf_ShutdownFile_RobotCommand_5fmessage_2eproto() {
- delete RobotCommand_message::default_instance_;
- delete RobotCommand_message_reflection_;
+ _RobotCommand_message_default_instance_.Shutdown();
+ delete file_level_metadata[0].reflection;
}
-void protobuf_AddDesc_RobotCommand_5fmessage_2eproto() {
- static bool already_here = false;
- if (already_here) return;
- already_here = true;
+void protobuf_InitDefaults_RobotCommand_5fmessage_2eproto_impl() {
GOOGLE_PROTOBUF_VERIFY_VERSION;
- ::protobuf_AddDesc_position_5fmessage_2eproto();
+ ::protobuf_InitDefaults_position_5fmessage_2eproto();
+ ::google::protobuf::internal::InitProtobufDefaults();
+ _RobotCommand_message_default_instance_.DefaultConstruct();
+ _RobotCommand_message_default_instance_.get_mutable()->fin_pos_ = const_cast< ::position_message*>(
+ ::position_message::internal_default_instance());
+ _RobotCommand_message_default_instance_.get_mutable()->fin_vel_ = const_cast< ::position_message*>(
+ ::position_message::internal_default_instance());
+}
+
+void protobuf_InitDefaults_RobotCommand_5fmessage_2eproto() {
+ static GOOGLE_PROTOBUF_DECLARE_ONCE(once);
+ ::google::protobuf::GoogleOnceInit(&once, &protobuf_InitDefaults_RobotCommand_5fmessage_2eproto_impl);
+}
+void protobuf_AddDesc_RobotCommand_5fmessage_2eproto_impl() {
+ protobuf_InitDefaults_RobotCommand_5fmessage_2eproto();
+ static const char descriptor[] = {
+ "\n\032RobotCommand_message.proto\032\026position_m"
+ "essage.proto\"\316\001\n\024RobotCommand_message\022\"\n"
+ "\007fin_pos\030\001 \002(\0132\021.position_message\022\"\n\007fin"
+ "_vel\030\002 \002(\0132\021.position_message\022\020\n\010maxSpee"
+ "d\030\003 \002(\002\022\022\n\nkickspeedx\030\004 \002(\002\022\022\n\nkickspeed"
+ "z\030\005 \002(\002\022\016\n\006useNav\030\006 \002(\010\022\021\n\tisBallObs\030\007 \002"
+ "(\010\022\021\n\tisKickObs\030\010 \002(\010"
+ };
::google::protobuf::DescriptorPool::InternalAddGeneratedFile(
- "\n\032RobotCommand_message.proto\032\026position_m"
- "essage.proto\"\316\001\n\024RobotCommand_message\022\"\n"
- "\007fin_pos\030\001 \002(\0132\021.position_message\022\"\n\007fin"
- "_vel\030\002 \002(\0132\021.position_message\022\020\n\010maxSpee"
- "d\030\003 \002(\002\022\022\n\nkickspeedx\030\004 \002(\002\022\022\n\nkickspeed"
- "z\030\005 \002(\002\022\016\n\006useNav\030\006 \002(\010\022\021\n\tisBallObs\030\007 \002"
- "(\010\022\021\n\tisKickObs\030\010 \002(\010", 261);
+ descriptor, 261);
::google::protobuf::MessageFactory::InternalRegisterGeneratedFile(
"RobotCommand_message.proto", &protobuf_RegisterTypes);
- RobotCommand_message::default_instance_ = new RobotCommand_message();
- RobotCommand_message::default_instance_->InitAsDefaultInstance();
+ ::protobuf_AddDesc_position_5fmessage_2eproto();
::google::protobuf::internal::OnShutdown(&protobuf_ShutdownFile_RobotCommand_5fmessage_2eproto);
}
+GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AddDesc_RobotCommand_5fmessage_2eproto_once_);
+void protobuf_AddDesc_RobotCommand_5fmessage_2eproto() {
+ ::google::protobuf::GoogleOnceInit(&protobuf_AddDesc_RobotCommand_5fmessage_2eproto_once_,
+ &protobuf_AddDesc_RobotCommand_5fmessage_2eproto_impl);
+}
// Force AddDescriptors() to be called at static initialization time.
struct StaticDescriptorInitializer_RobotCommand_5fmessage_2eproto {
StaticDescriptorInitializer_RobotCommand_5fmessage_2eproto() {
@@ -107,7 +138,7 @@ struct StaticDescriptorInitializer_RobotCommand_5fmessage_2eproto {
// ===================================================================
-#ifndef _MSC_VER
+#if !defined(_MSC_VER) || _MSC_VER >= 1900
const int RobotCommand_message::kFinPosFieldNumber;
const int RobotCommand_message::kFinVelFieldNumber;
const int RobotCommand_message::kMaxSpeedFieldNumber;
@@ -116,44 +147,54 @@ const int RobotCommand_message::kKickspeedzFieldNumber;
const int RobotCommand_message::kUseNavFieldNumber;
const int RobotCommand_message::kIsBallObsFieldNumber;
const int RobotCommand_message::kIsKickObsFieldNumber;
-#endif // !_MSC_VER
+#endif // !defined(_MSC_VER) || _MSC_VER >= 1900
RobotCommand_message::RobotCommand_message()
- : ::google::protobuf::Message() {
+ : ::google::protobuf::Message(), _internal_metadata_(NULL) {
+ if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) {
+ protobuf_InitDefaults_RobotCommand_5fmessage_2eproto();
+ }
SharedCtor();
+ // @@protoc_insertion_point(constructor:RobotCommand_message)
}
-
-void RobotCommand_message::InitAsDefaultInstance() {
- fin_pos_ = const_cast< ::position_message*>(&::position_message::default_instance());
- fin_vel_ = const_cast< ::position_message*>(&::position_message::default_instance());
-}
-
RobotCommand_message::RobotCommand_message(const RobotCommand_message& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
+ : ::google::protobuf::Message(),
+ _internal_metadata_(NULL),
+ _has_bits_(from._has_bits_),
+ _cached_size_(0) {
+ _internal_metadata_.MergeFrom(from._internal_metadata_);
+ if (from.has_fin_pos()) {
+ fin_pos_ = new ::position_message(*from.fin_pos_);
+ } else {
+ fin_pos_ = NULL;
+ }
+ if (from.has_fin_vel()) {
+ fin_vel_ = new ::position_message(*from.fin_vel_);
+ } else {
+ fin_vel_ = NULL;
+ }
+ ::memcpy(&maxspeed_, &from.maxspeed_,
+ reinterpret_cast(&iskickobs_) -
+ reinterpret_cast(&maxspeed_) + sizeof(iskickobs_));
+ // @@protoc_insertion_point(copy_constructor:RobotCommand_message)
}
void RobotCommand_message::SharedCtor() {
_cached_size_ = 0;
- fin_pos_ = NULL;
- fin_vel_ = NULL;
- maxspeed_ = 0;
- kickspeedx_ = 0;
- kickspeedz_ = 0;
- usenav_ = false;
- isballobs_ = false;
- iskickobs_ = false;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ ::memset(&fin_pos_, 0, reinterpret_cast(&iskickobs_) -
+ reinterpret_cast(&fin_pos_) + sizeof(iskickobs_));
}
RobotCommand_message::~RobotCommand_message() {
+ // @@protoc_insertion_point(destructor:RobotCommand_message)
SharedDtor();
}
void RobotCommand_message::SharedDtor() {
- if (this != default_instance_) {
+ if (this != internal_default_instance()) {
delete fin_pos_;
+ }
+ if (this != internal_default_instance()) {
delete fin_vel_;
}
}
@@ -165,173 +206,158 @@ void RobotCommand_message::SetCachedSize(int size) const {
}
const ::google::protobuf::Descriptor* RobotCommand_message::descriptor() {
protobuf_AssignDescriptorsOnce();
- return RobotCommand_message_descriptor_;
+ return file_level_metadata[0].descriptor;
}
const RobotCommand_message& RobotCommand_message::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_RobotCommand_5fmessage_2eproto();
- return *default_instance_;
+ protobuf_InitDefaults_RobotCommand_5fmessage_2eproto();
+ return *internal_default_instance();
}
-RobotCommand_message* RobotCommand_message::default_instance_ = NULL;
-
-RobotCommand_message* RobotCommand_message::New() const {
- return new RobotCommand_message;
+RobotCommand_message* RobotCommand_message::New(::google::protobuf::Arena* arena) const {
+ RobotCommand_message* n = new RobotCommand_message;
+ if (arena != NULL) {
+ arena->Own(n);
+ }
+ return n;
}
void RobotCommand_message::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+// @@protoc_insertion_point(message_clear_start:RobotCommand_message)
+ if (_has_bits_[0 / 32] & 3u) {
if (has_fin_pos()) {
- if (fin_pos_ != NULL) fin_pos_->::position_message::Clear();
+ GOOGLE_DCHECK(fin_pos_ != NULL);
+ fin_pos_->::position_message::Clear();
}
if (has_fin_vel()) {
- if (fin_vel_ != NULL) fin_vel_->::position_message::Clear();
+ GOOGLE_DCHECK(fin_vel_ != NULL);
+ fin_vel_->::position_message::Clear();
}
- maxspeed_ = 0;
- kickspeedx_ = 0;
- kickspeedz_ = 0;
- usenav_ = false;
- isballobs_ = false;
- iskickobs_ = false;
}
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
+ if (_has_bits_[0 / 32] & 252u) {
+ ::memset(&maxspeed_, 0, reinterpret_cast(&iskickobs_) -
+ reinterpret_cast(&maxspeed_) + sizeof(iskickobs_));
+ }
+ _has_bits_.Clear();
+ _internal_metadata_.Clear();
}
bool RobotCommand_message::MergePartialFromCodedStream(
::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure
::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
+ // @@protoc_insertion_point(parse_start:RobotCommand_message)
+ for (;;) {
+ ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u);
+ tag = p.first;
+ if (!p.second) goto handle_unusual;
switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
// required .position_message fin_pos = 1;
case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
+ if (tag == 10u) {
DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
input, mutable_fin_pos()));
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(18)) goto parse_fin_vel;
break;
}
// required .position_message fin_vel = 2;
case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_fin_vel:
+ if (tag == 18u) {
DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
input, mutable_fin_vel()));
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(29)) goto parse_maxSpeed;
break;
}
// required float maxSpeed = 3;
case 3: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_maxSpeed:
+ if (tag == 29u) {
+ set_has_maxspeed();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
input, &maxspeed_)));
- set_has_maxspeed();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(37)) goto parse_kickspeedx;
break;
}
// required float kickspeedx = 4;
case 4: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_kickspeedx:
+ if (tag == 37u) {
+ set_has_kickspeedx();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
input, &kickspeedx_)));
- set_has_kickspeedx();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(45)) goto parse_kickspeedz;
break;
}
// required float kickspeedz = 5;
case 5: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_kickspeedz:
+ if (tag == 45u) {
+ set_has_kickspeedz();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
input, &kickspeedz_)));
- set_has_kickspeedz();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(48)) goto parse_useNav;
break;
}
// required bool useNav = 6;
case 6: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_useNav:
+ if (tag == 48u) {
+ set_has_usenav();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>(
input, &usenav_)));
- set_has_usenav();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(56)) goto parse_isBallObs;
break;
}
// required bool isBallObs = 7;
case 7: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_isBallObs:
+ if (tag == 56u) {
+ set_has_isballobs();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>(
input, &isballobs_)));
- set_has_isballobs();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(64)) goto parse_isKickObs;
break;
}
// required bool isKickObs = 8;
case 8: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_isKickObs:
+ if (tag == 64u) {
+ set_has_iskickobs();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>(
input, &iskickobs_)));
- set_has_iskickobs();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectAtEnd()) return true;
break;
}
default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ handle_unusual:
+ if (tag == 0 ||
+ ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
+ goto success;
}
DO_(::google::protobuf::internal::WireFormat::SkipField(
input, tag, mutable_unknown_fields()));
@@ -339,22 +365,28 @@ bool RobotCommand_message::MergePartialFromCodedStream(
}
}
}
+success:
+ // @@protoc_insertion_point(parse_success:RobotCommand_message)
return true;
+failure:
+ // @@protoc_insertion_point(parse_failure:RobotCommand_message)
+ return false;
#undef DO_
}
void RobotCommand_message::SerializeWithCachedSizes(
::google::protobuf::io::CodedOutputStream* output) const {
+ // @@protoc_insertion_point(serialize_start:RobotCommand_message)
// required .position_message fin_pos = 1;
if (has_fin_pos()) {
::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 1, this->fin_pos(), output);
+ 1, *this->fin_pos_, output);
}
// required .position_message fin_vel = 2;
if (has_fin_vel()) {
::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 2, this->fin_vel(), output);
+ 2, *this->fin_vel_, output);
}
// required float maxSpeed = 3;
@@ -387,26 +419,29 @@ void RobotCommand_message::SerializeWithCachedSizes(
::google::protobuf::internal::WireFormatLite::WriteBool(8, this->iskickobs(), output);
}
- if (!unknown_fields().empty()) {
+ if (_internal_metadata_.have_unknown_fields()) {
::google::protobuf::internal::WireFormat::SerializeUnknownFields(
unknown_fields(), output);
}
+ // @@protoc_insertion_point(serialize_end:RobotCommand_message)
}
-::google::protobuf::uint8* RobotCommand_message::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
+::google::protobuf::uint8* RobotCommand_message::InternalSerializeWithCachedSizesToArray(
+ bool deterministic, ::google::protobuf::uint8* target) const {
+ (void)deterministic; // Unused
+ // @@protoc_insertion_point(serialize_to_array_start:RobotCommand_message)
// required .position_message fin_pos = 1;
if (has_fin_pos()) {
target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 1, this->fin_pos(), target);
+ InternalWriteMessageNoVirtualToArray(
+ 1, *this->fin_pos_, false, target);
}
// required .position_message fin_vel = 2;
if (has_fin_vel()) {
target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 2, this->fin_vel(), target);
+ InternalWriteMessageNoVirtualToArray(
+ 2, *this->fin_vel_, false, target);
}
// required float maxSpeed = 3;
@@ -439,88 +474,132 @@ ::google::protobuf::uint8* RobotCommand_message::SerializeWithCachedSizesToArray
target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(8, this->iskickobs(), target);
}
- if (!unknown_fields().empty()) {
+ if (_internal_metadata_.have_unknown_fields()) {
target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
unknown_fields(), target);
}
+ // @@protoc_insertion_point(serialize_to_array_end:RobotCommand_message)
return target;
}
-int RobotCommand_message::ByteSize() const {
- int total_size = 0;
+size_t RobotCommand_message::RequiredFieldsByteSizeFallback() const {
+// @@protoc_insertion_point(required_fields_byte_size_fallback_start:RobotCommand_message)
+ size_t total_size = 0;
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (has_fin_pos()) {
// required .position_message fin_pos = 1;
- if (has_fin_pos()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->fin_pos());
- }
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ *this->fin_pos_);
+ }
+ if (has_fin_vel()) {
// required .position_message fin_vel = 2;
- if (has_fin_vel()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->fin_vel());
- }
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ *this->fin_vel_);
+ }
+ if (has_maxspeed()) {
// required float maxSpeed = 3;
- if (has_maxspeed()) {
- total_size += 1 + 4;
- }
+ total_size += 1 + 4;
+ }
+ if (has_kickspeedx()) {
// required float kickspeedx = 4;
- if (has_kickspeedx()) {
- total_size += 1 + 4;
- }
+ total_size += 1 + 4;
+ }
+ if (has_kickspeedz()) {
// required float kickspeedz = 5;
- if (has_kickspeedz()) {
- total_size += 1 + 4;
- }
+ total_size += 1 + 4;
+ }
+ if (has_usenav()) {
// required bool useNav = 6;
- if (has_usenav()) {
- total_size += 1 + 1;
- }
+ total_size += 1 + 1;
+ }
+ if (has_isballobs()) {
// required bool isBallObs = 7;
- if (has_isballobs()) {
- total_size += 1 + 1;
- }
+ total_size += 1 + 1;
+ }
+ if (has_iskickobs()) {
// required bool isKickObs = 8;
- if (has_iskickobs()) {
- total_size += 1 + 1;
- }
-
+ total_size += 1 + 1;
}
- if (!unknown_fields().empty()) {
+
+ return total_size;
+}
+size_t RobotCommand_message::ByteSizeLong() const {
+// @@protoc_insertion_point(message_byte_size_start:RobotCommand_message)
+ size_t total_size = 0;
+
+ if (_internal_metadata_.have_unknown_fields()) {
total_size +=
::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
unknown_fields());
}
+ if (((_has_bits_[0] & 0x000000ff) ^ 0x000000ff) == 0) { // All required fields are present.
+ // required .position_message fin_pos = 1;
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ *this->fin_pos_);
+
+ // required .position_message fin_vel = 2;
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ *this->fin_vel_);
+
+ // required float maxSpeed = 3;
+ total_size += 1 + 4;
+
+ // required float kickspeedx = 4;
+ total_size += 1 + 4;
+
+ // required float kickspeedz = 5;
+ total_size += 1 + 4;
+
+ // required bool useNav = 6;
+ total_size += 1 + 1;
+
+ // required bool isBallObs = 7;
+ total_size += 1 + 1;
+
+ // required bool isKickObs = 8;
+ total_size += 1 + 1;
+
+ } else {
+ total_size += RequiredFieldsByteSizeFallback();
+ }
+ int cached_size = ::google::protobuf::internal::ToCachedSize(total_size);
GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
+ _cached_size_ = cached_size;
GOOGLE_SAFE_CONCURRENT_WRITES_END();
return total_size;
}
void RobotCommand_message::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
+// @@protoc_insertion_point(generalized_merge_from_start:RobotCommand_message)
+ GOOGLE_DCHECK_NE(&from, this);
const RobotCommand_message* source =
- ::google::protobuf::internal::dynamic_cast_if_available(
- &from);
+ ::google::protobuf::internal::DynamicCastToGenerated(
+ &from);
if (source == NULL) {
+ // @@protoc_insertion_point(generalized_merge_from_cast_fail:RobotCommand_message)
::google::protobuf::internal::ReflectionOps::Merge(from, this);
} else {
+ // @@protoc_insertion_point(generalized_merge_from_cast_success:RobotCommand_message)
MergeFrom(*source);
}
}
void RobotCommand_message::MergeFrom(const RobotCommand_message& from) {
- GOOGLE_CHECK_NE(&from, this);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+// @@protoc_insertion_point(class_specific_merge_from_start:RobotCommand_message)
+ GOOGLE_DCHECK_NE(&from, this);
+ _internal_metadata_.MergeFrom(from._internal_metadata_);
+ if (from._has_bits_[0 / 32] & 255u) {
if (from.has_fin_pos()) {
mutable_fin_pos()->::position_message::MergeFrom(from.fin_pos());
}
@@ -546,16 +625,17 @@ void RobotCommand_message::MergeFrom(const RobotCommand_message& from) {
set_iskickobs(from.iskickobs());
}
}
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
}
void RobotCommand_message::CopyFrom(const ::google::protobuf::Message& from) {
+// @@protoc_insertion_point(generalized_copy_from_start:RobotCommand_message)
if (&from == this) return;
Clear();
MergeFrom(from);
}
void RobotCommand_message::CopyFrom(const RobotCommand_message& from) {
+// @@protoc_insertion_point(class_specific_copy_from_start:RobotCommand_message)
if (&from == this) return;
Clear();
MergeFrom(from);
@@ -563,40 +643,276 @@ void RobotCommand_message::CopyFrom(const RobotCommand_message& from) {
bool RobotCommand_message::IsInitialized() const {
if ((_has_bits_[0] & 0x000000ff) != 0x000000ff) return false;
-
if (has_fin_pos()) {
- if (!this->fin_pos().IsInitialized()) return false;
+ if (!this->fin_pos_->IsInitialized()) return false;
}
if (has_fin_vel()) {
- if (!this->fin_vel().IsInitialized()) return false;
+ if (!this->fin_vel_->IsInitialized()) return false;
}
return true;
}
void RobotCommand_message::Swap(RobotCommand_message* other) {
- if (other != this) {
- std::swap(fin_pos_, other->fin_pos_);
- std::swap(fin_vel_, other->fin_vel_);
- std::swap(maxspeed_, other->maxspeed_);
- std::swap(kickspeedx_, other->kickspeedx_);
- std::swap(kickspeedz_, other->kickspeedz_);
- std::swap(usenav_, other->usenav_);
- std::swap(isballobs_, other->isballobs_);
- std::swap(iskickobs_, other->iskickobs_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
+ if (other == this) return;
+ InternalSwap(other);
+}
+void RobotCommand_message::InternalSwap(RobotCommand_message* other) {
+ std::swap(fin_pos_, other->fin_pos_);
+ std::swap(fin_vel_, other->fin_vel_);
+ std::swap(maxspeed_, other->maxspeed_);
+ std::swap(kickspeedx_, other->kickspeedx_);
+ std::swap(kickspeedz_, other->kickspeedz_);
+ std::swap(usenav_, other->usenav_);
+ std::swap(isballobs_, other->isballobs_);
+ std::swap(iskickobs_, other->iskickobs_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _internal_metadata_.Swap(&other->_internal_metadata_);
+ std::swap(_cached_size_, other->_cached_size_);
}
::google::protobuf::Metadata RobotCommand_message::GetMetadata() const {
protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = RobotCommand_message_descriptor_;
- metadata.reflection = RobotCommand_message_reflection_;
- return metadata;
+ return file_level_metadata[0];
+}
+
+#if PROTOBUF_INLINE_NOT_IN_HEADERS
+// RobotCommand_message
+
+// required .position_message fin_pos = 1;
+bool RobotCommand_message::has_fin_pos() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+void RobotCommand_message::set_has_fin_pos() {
+ _has_bits_[0] |= 0x00000001u;
+}
+void RobotCommand_message::clear_has_fin_pos() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+void RobotCommand_message::clear_fin_pos() {
+ if (fin_pos_ != NULL) fin_pos_->::position_message::Clear();
+ clear_has_fin_pos();
+}
+const ::position_message& RobotCommand_message::fin_pos() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.fin_pos)
+ return fin_pos_ != NULL ? *fin_pos_
+ : *::position_message::internal_default_instance();
+}
+::position_message* RobotCommand_message::mutable_fin_pos() {
+ set_has_fin_pos();
+ if (fin_pos_ == NULL) {
+ fin_pos_ = new ::position_message;
+ }
+ // @@protoc_insertion_point(field_mutable:RobotCommand_message.fin_pos)
+ return fin_pos_;
+}
+::position_message* RobotCommand_message::release_fin_pos() {
+ // @@protoc_insertion_point(field_release:RobotCommand_message.fin_pos)
+ clear_has_fin_pos();
+ ::position_message* temp = fin_pos_;
+ fin_pos_ = NULL;
+ return temp;
+}
+void RobotCommand_message::set_allocated_fin_pos(::position_message* fin_pos) {
+ delete fin_pos_;
+ fin_pos_ = fin_pos;
+ if (fin_pos) {
+ set_has_fin_pos();
+ } else {
+ clear_has_fin_pos();
+ }
+ // @@protoc_insertion_point(field_set_allocated:RobotCommand_message.fin_pos)
+}
+
+// required .position_message fin_vel = 2;
+bool RobotCommand_message::has_fin_vel() const {
+ return (_has_bits_[0] & 0x00000002u) != 0;
+}
+void RobotCommand_message::set_has_fin_vel() {
+ _has_bits_[0] |= 0x00000002u;
+}
+void RobotCommand_message::clear_has_fin_vel() {
+ _has_bits_[0] &= ~0x00000002u;
+}
+void RobotCommand_message::clear_fin_vel() {
+ if (fin_vel_ != NULL) fin_vel_->::position_message::Clear();
+ clear_has_fin_vel();
+}
+const ::position_message& RobotCommand_message::fin_vel() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.fin_vel)
+ return fin_vel_ != NULL ? *fin_vel_
+ : *::position_message::internal_default_instance();
+}
+::position_message* RobotCommand_message::mutable_fin_vel() {
+ set_has_fin_vel();
+ if (fin_vel_ == NULL) {
+ fin_vel_ = new ::position_message;
+ }
+ // @@protoc_insertion_point(field_mutable:RobotCommand_message.fin_vel)
+ return fin_vel_;
+}
+::position_message* RobotCommand_message::release_fin_vel() {
+ // @@protoc_insertion_point(field_release:RobotCommand_message.fin_vel)
+ clear_has_fin_vel();
+ ::position_message* temp = fin_vel_;
+ fin_vel_ = NULL;
+ return temp;
+}
+void RobotCommand_message::set_allocated_fin_vel(::position_message* fin_vel) {
+ delete fin_vel_;
+ fin_vel_ = fin_vel;
+ if (fin_vel) {
+ set_has_fin_vel();
+ } else {
+ clear_has_fin_vel();
+ }
+ // @@protoc_insertion_point(field_set_allocated:RobotCommand_message.fin_vel)
+}
+
+// required float maxSpeed = 3;
+bool RobotCommand_message::has_maxspeed() const {
+ return (_has_bits_[0] & 0x00000004u) != 0;
+}
+void RobotCommand_message::set_has_maxspeed() {
+ _has_bits_[0] |= 0x00000004u;
+}
+void RobotCommand_message::clear_has_maxspeed() {
+ _has_bits_[0] &= ~0x00000004u;
+}
+void RobotCommand_message::clear_maxspeed() {
+ maxspeed_ = 0;
+ clear_has_maxspeed();
+}
+float RobotCommand_message::maxspeed() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.maxSpeed)
+ return maxspeed_;
+}
+void RobotCommand_message::set_maxspeed(float value) {
+ set_has_maxspeed();
+ maxspeed_ = value;
+ // @@protoc_insertion_point(field_set:RobotCommand_message.maxSpeed)
+}
+
+// required float kickspeedx = 4;
+bool RobotCommand_message::has_kickspeedx() const {
+ return (_has_bits_[0] & 0x00000008u) != 0;
+}
+void RobotCommand_message::set_has_kickspeedx() {
+ _has_bits_[0] |= 0x00000008u;
+}
+void RobotCommand_message::clear_has_kickspeedx() {
+ _has_bits_[0] &= ~0x00000008u;
+}
+void RobotCommand_message::clear_kickspeedx() {
+ kickspeedx_ = 0;
+ clear_has_kickspeedx();
+}
+float RobotCommand_message::kickspeedx() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.kickspeedx)
+ return kickspeedx_;
+}
+void RobotCommand_message::set_kickspeedx(float value) {
+ set_has_kickspeedx();
+ kickspeedx_ = value;
+ // @@protoc_insertion_point(field_set:RobotCommand_message.kickspeedx)
+}
+
+// required float kickspeedz = 5;
+bool RobotCommand_message::has_kickspeedz() const {
+ return (_has_bits_[0] & 0x00000010u) != 0;
+}
+void RobotCommand_message::set_has_kickspeedz() {
+ _has_bits_[0] |= 0x00000010u;
+}
+void RobotCommand_message::clear_has_kickspeedz() {
+ _has_bits_[0] &= ~0x00000010u;
+}
+void RobotCommand_message::clear_kickspeedz() {
+ kickspeedz_ = 0;
+ clear_has_kickspeedz();
+}
+float RobotCommand_message::kickspeedz() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.kickspeedz)
+ return kickspeedz_;
+}
+void RobotCommand_message::set_kickspeedz(float value) {
+ set_has_kickspeedz();
+ kickspeedz_ = value;
+ // @@protoc_insertion_point(field_set:RobotCommand_message.kickspeedz)
+}
+
+// required bool useNav = 6;
+bool RobotCommand_message::has_usenav() const {
+ return (_has_bits_[0] & 0x00000020u) != 0;
+}
+void RobotCommand_message::set_has_usenav() {
+ _has_bits_[0] |= 0x00000020u;
+}
+void RobotCommand_message::clear_has_usenav() {
+ _has_bits_[0] &= ~0x00000020u;
+}
+void RobotCommand_message::clear_usenav() {
+ usenav_ = false;
+ clear_has_usenav();
+}
+bool RobotCommand_message::usenav() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.useNav)
+ return usenav_;
+}
+void RobotCommand_message::set_usenav(bool value) {
+ set_has_usenav();
+ usenav_ = value;
+ // @@protoc_insertion_point(field_set:RobotCommand_message.useNav)
+}
+
+// required bool isBallObs = 7;
+bool RobotCommand_message::has_isballobs() const {
+ return (_has_bits_[0] & 0x00000040u) != 0;
+}
+void RobotCommand_message::set_has_isballobs() {
+ _has_bits_[0] |= 0x00000040u;
+}
+void RobotCommand_message::clear_has_isballobs() {
+ _has_bits_[0] &= ~0x00000040u;
+}
+void RobotCommand_message::clear_isballobs() {
+ isballobs_ = false;
+ clear_has_isballobs();
+}
+bool RobotCommand_message::isballobs() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.isBallObs)
+ return isballobs_;
+}
+void RobotCommand_message::set_isballobs(bool value) {
+ set_has_isballobs();
+ isballobs_ = value;
+ // @@protoc_insertion_point(field_set:RobotCommand_message.isBallObs)
+}
+
+// required bool isKickObs = 8;
+bool RobotCommand_message::has_iskickobs() const {
+ return (_has_bits_[0] & 0x00000080u) != 0;
+}
+void RobotCommand_message::set_has_iskickobs() {
+ _has_bits_[0] |= 0x00000080u;
+}
+void RobotCommand_message::clear_has_iskickobs() {
+ _has_bits_[0] &= ~0x00000080u;
+}
+void RobotCommand_message::clear_iskickobs() {
+ iskickobs_ = false;
+ clear_has_iskickobs();
+}
+bool RobotCommand_message::iskickobs() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.isKickObs)
+ return iskickobs_;
+}
+void RobotCommand_message::set_iskickobs(bool value) {
+ set_has_iskickobs();
+ iskickobs_ = value;
+ // @@protoc_insertion_point(field_set:RobotCommand_message.isKickObs)
}
+#endif // PROTOBUF_INLINE_NOT_IN_HEADERS
// @@protoc_insertion_point(namespace_scope)
diff --git a/src/proto/RobotCommand_message.pb.h b/src/proto/RobotCommand_message.pb.h
index 6a1acc5..4d8ee31 100644
--- a/src/proto/RobotCommand_message.pb.h
+++ b/src/proto/RobotCommand_message.pb.h
@@ -8,35 +8,41 @@
#include
-#if GOOGLE_PROTOBUF_VERSION < 2005000
+#if GOOGLE_PROTOBUF_VERSION < 3001000
#error This file was generated by a newer version of protoc which is
#error incompatible with your Protocol Buffer headers. Please update
#error your headers.
#endif
-#if 2005000 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION
+#if 3001000 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION
#error This file was generated by an older version of protoc which is
#error incompatible with your Protocol Buffer headers. Please
#error regenerate this file with a newer version of protoc.
#endif
+#include
+#include
#include
+#include
#include
-#include
-#include
+#include // IWYU pragma: export
+#include // IWYU pragma: export
#include
#include "position_message.pb.h"
// @@protoc_insertion_point(includes)
+class RobotCommand_message;
+class RobotCommand_messageDefaultTypeInternal;
+extern RobotCommand_messageDefaultTypeInternal _RobotCommand_message_default_instance_;
+class position_message;
+class position_messageDefaultTypeInternal;
+extern position_messageDefaultTypeInternal _position_message_default_instance_;
// Internal implementation detail -- do not call these.
-void protobuf_AddDesc_RobotCommand_5fmessage_2eproto();
-void protobuf_AssignDesc_RobotCommand_5fmessage_2eproto();
-void protobuf_ShutdownFile_RobotCommand_5fmessage_2eproto();
-
-class RobotCommand_message;
+void protobuf_AddDesc_RobotCommand_5fmessage_2eproto();
+void protobuf_InitDefaults_RobotCommand_5fmessage_2eproto();
// ===================================================================
-class RobotCommand_message : public ::google::protobuf::Message {
+class RobotCommand_message : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:RobotCommand_message) */ {
public:
RobotCommand_message();
virtual ~RobotCommand_message();
@@ -49,128 +55,152 @@ class RobotCommand_message : public ::google::protobuf::Message {
}
inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
+ return _internal_metadata_.unknown_fields();
}
inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
+ return _internal_metadata_.mutable_unknown_fields();
}
static const ::google::protobuf::Descriptor* descriptor();
static const RobotCommand_message& default_instance();
+ static inline const RobotCommand_message* internal_default_instance() {
+ return reinterpret_cast(
+ &_RobotCommand_message_default_instance_);
+ }
+
void Swap(RobotCommand_message* other);
// implements Message ----------------------------------------------
- RobotCommand_message* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
+ inline RobotCommand_message* New() const PROTOBUF_FINAL { return New(NULL); }
+
+ RobotCommand_message* New(::google::protobuf::Arena* arena) const PROTOBUF_FINAL;
+ void CopyFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL;
+ void MergeFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL;
void CopyFrom(const RobotCommand_message& from);
void MergeFrom(const RobotCommand_message& from);
- void Clear();
- bool IsInitialized() const;
+ void Clear() PROTOBUF_FINAL;
+ bool IsInitialized() const PROTOBUF_FINAL;
- int ByteSize() const;
+ size_t ByteSizeLong() const PROTOBUF_FINAL;
bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
+ ::google::protobuf::io::CodedInputStream* input) PROTOBUF_FINAL;
void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
+ ::google::protobuf::io::CodedOutputStream* output) const PROTOBUF_FINAL;
+ ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray(
+ bool deterministic, ::google::protobuf::uint8* target) const PROTOBUF_FINAL;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output)
+ const PROTOBUF_FINAL {
+ return InternalSerializeWithCachedSizesToArray(false, output);
+ }
+ int GetCachedSize() const PROTOBUF_FINAL { return _cached_size_; }
private:
void SharedCtor();
void SharedDtor();
- void SetCachedSize(int size) const;
+ void SetCachedSize(int size) const PROTOBUF_FINAL;
+ void InternalSwap(RobotCommand_message* other);
+ private:
+ inline ::google::protobuf::Arena* GetArenaNoVirtual() const {
+ return NULL;
+ }
+ inline void* MaybeArenaPtr() const {
+ return NULL;
+ }
public:
- ::google::protobuf::Metadata GetMetadata() const;
+ ::google::protobuf::Metadata GetMetadata() const PROTOBUF_FINAL;
// nested types ----------------------------------------------------
// accessors -------------------------------------------------------
// required .position_message fin_pos = 1;
- inline bool has_fin_pos() const;
- inline void clear_fin_pos();
+ bool has_fin_pos() const;
+ void clear_fin_pos();
static const int kFinPosFieldNumber = 1;
- inline const ::position_message& fin_pos() const;
- inline ::position_message* mutable_fin_pos();
- inline ::position_message* release_fin_pos();
- inline void set_allocated_fin_pos(::position_message* fin_pos);
+ const ::position_message& fin_pos() const;
+ ::position_message* mutable_fin_pos();
+ ::position_message* release_fin_pos();
+ void set_allocated_fin_pos(::position_message* fin_pos);
// required .position_message fin_vel = 2;
- inline bool has_fin_vel() const;
- inline void clear_fin_vel();
+ bool has_fin_vel() const;
+ void clear_fin_vel();
static const int kFinVelFieldNumber = 2;
- inline const ::position_message& fin_vel() const;
- inline ::position_message* mutable_fin_vel();
- inline ::position_message* release_fin_vel();
- inline void set_allocated_fin_vel(::position_message* fin_vel);
+ const ::position_message& fin_vel() const;
+ ::position_message* mutable_fin_vel();
+ ::position_message* release_fin_vel();
+ void set_allocated_fin_vel(::position_message* fin_vel);
// required float maxSpeed = 3;
- inline bool has_maxspeed() const;
- inline void clear_maxspeed();
+ bool has_maxspeed() const;
+ void clear_maxspeed();
static const int kMaxSpeedFieldNumber = 3;
- inline float maxspeed() const;
- inline void set_maxspeed(float value);
+ float maxspeed() const;
+ void set_maxspeed(float value);
// required float kickspeedx = 4;
- inline bool has_kickspeedx() const;
- inline void clear_kickspeedx();
+ bool has_kickspeedx() const;
+ void clear_kickspeedx();
static const int kKickspeedxFieldNumber = 4;
- inline float kickspeedx() const;
- inline void set_kickspeedx(float value);
+ float kickspeedx() const;
+ void set_kickspeedx(float value);
// required float kickspeedz = 5;
- inline bool has_kickspeedz() const;
- inline void clear_kickspeedz();
+ bool has_kickspeedz() const;
+ void clear_kickspeedz();
static const int kKickspeedzFieldNumber = 5;
- inline float kickspeedz() const;
- inline void set_kickspeedz(float value);
+ float kickspeedz() const;
+ void set_kickspeedz(float value);
// required bool useNav = 6;
- inline bool has_usenav() const;
- inline void clear_usenav();
+ bool has_usenav() const;
+ void clear_usenav();
static const int kUseNavFieldNumber = 6;
- inline bool usenav() const;
- inline void set_usenav(bool value);
+ bool usenav() const;
+ void set_usenav(bool value);
// required bool isBallObs = 7;
- inline bool has_isballobs() const;
- inline void clear_isballobs();
+ bool has_isballobs() const;
+ void clear_isballobs();
static const int kIsBallObsFieldNumber = 7;
- inline bool isballobs() const;
- inline void set_isballobs(bool value);
+ bool isballobs() const;
+ void set_isballobs(bool value);
// required bool isKickObs = 8;
- inline bool has_iskickobs() const;
- inline void clear_iskickobs();
+ bool has_iskickobs() const;
+ void clear_iskickobs();
static const int kIsKickObsFieldNumber = 8;
- inline bool iskickobs() const;
- inline void set_iskickobs(bool value);
+ bool iskickobs() const;
+ void set_iskickobs(bool value);
// @@protoc_insertion_point(class_scope:RobotCommand_message)
private:
- inline void set_has_fin_pos();
- inline void clear_has_fin_pos();
- inline void set_has_fin_vel();
- inline void clear_has_fin_vel();
- inline void set_has_maxspeed();
- inline void clear_has_maxspeed();
- inline void set_has_kickspeedx();
- inline void clear_has_kickspeedx();
- inline void set_has_kickspeedz();
- inline void clear_has_kickspeedz();
- inline void set_has_usenav();
- inline void clear_has_usenav();
- inline void set_has_isballobs();
- inline void clear_has_isballobs();
- inline void set_has_iskickobs();
- inline void clear_has_iskickobs();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
+ void set_has_fin_pos();
+ void clear_has_fin_pos();
+ void set_has_fin_vel();
+ void clear_has_fin_vel();
+ void set_has_maxspeed();
+ void clear_has_maxspeed();
+ void set_has_kickspeedx();
+ void clear_has_kickspeedx();
+ void set_has_kickspeedz();
+ void clear_has_kickspeedz();
+ void set_has_usenav();
+ void clear_has_usenav();
+ void set_has_isballobs();
+ void clear_has_isballobs();
+ void set_has_iskickobs();
+ void clear_has_iskickobs();
+
+ // helper for ByteSizeLong()
+ size_t RequiredFieldsByteSizeFallback() const;
+
+ ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_;
+ ::google::protobuf::internal::HasBits<1> _has_bits_;
+ mutable int _cached_size_;
::position_message* fin_pos_;
::position_message* fin_vel_;
float maxspeed_;
@@ -179,22 +209,18 @@ class RobotCommand_message : public ::google::protobuf::Message {
bool usenav_;
bool isballobs_;
bool iskickobs_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(8 + 31) / 32];
-
- friend void protobuf_AddDesc_RobotCommand_5fmessage_2eproto();
- friend void protobuf_AssignDesc_RobotCommand_5fmessage_2eproto();
+ friend void protobuf_InitDefaults_RobotCommand_5fmessage_2eproto_impl();
+ friend void protobuf_AddDesc_RobotCommand_5fmessage_2eproto_impl();
+ friend const ::google::protobuf::uint32* protobuf_Offsets_RobotCommand_5fmessage_2eproto();
friend void protobuf_ShutdownFile_RobotCommand_5fmessage_2eproto();
- void InitAsDefaultInstance();
- static RobotCommand_message* default_instance_;
};
// ===================================================================
// ===================================================================
+#if !PROTOBUF_INLINE_NOT_IN_HEADERS
// RobotCommand_message
// required .position_message fin_pos = 1;
@@ -212,14 +238,20 @@ inline void RobotCommand_message::clear_fin_pos() {
clear_has_fin_pos();
}
inline const ::position_message& RobotCommand_message::fin_pos() const {
- return fin_pos_ != NULL ? *fin_pos_ : *default_instance_->fin_pos_;
+ // @@protoc_insertion_point(field_get:RobotCommand_message.fin_pos)
+ return fin_pos_ != NULL ? *fin_pos_
+ : *::position_message::internal_default_instance();
}
inline ::position_message* RobotCommand_message::mutable_fin_pos() {
set_has_fin_pos();
- if (fin_pos_ == NULL) fin_pos_ = new ::position_message;
+ if (fin_pos_ == NULL) {
+ fin_pos_ = new ::position_message;
+ }
+ // @@protoc_insertion_point(field_mutable:RobotCommand_message.fin_pos)
return fin_pos_;
}
inline ::position_message* RobotCommand_message::release_fin_pos() {
+ // @@protoc_insertion_point(field_release:RobotCommand_message.fin_pos)
clear_has_fin_pos();
::position_message* temp = fin_pos_;
fin_pos_ = NULL;
@@ -233,6 +265,7 @@ inline void RobotCommand_message::set_allocated_fin_pos(::position_message* fin_
} else {
clear_has_fin_pos();
}
+ // @@protoc_insertion_point(field_set_allocated:RobotCommand_message.fin_pos)
}
// required .position_message fin_vel = 2;
@@ -250,14 +283,20 @@ inline void RobotCommand_message::clear_fin_vel() {
clear_has_fin_vel();
}
inline const ::position_message& RobotCommand_message::fin_vel() const {
- return fin_vel_ != NULL ? *fin_vel_ : *default_instance_->fin_vel_;
+ // @@protoc_insertion_point(field_get:RobotCommand_message.fin_vel)
+ return fin_vel_ != NULL ? *fin_vel_
+ : *::position_message::internal_default_instance();
}
inline ::position_message* RobotCommand_message::mutable_fin_vel() {
set_has_fin_vel();
- if (fin_vel_ == NULL) fin_vel_ = new ::position_message;
+ if (fin_vel_ == NULL) {
+ fin_vel_ = new ::position_message;
+ }
+ // @@protoc_insertion_point(field_mutable:RobotCommand_message.fin_vel)
return fin_vel_;
}
inline ::position_message* RobotCommand_message::release_fin_vel() {
+ // @@protoc_insertion_point(field_release:RobotCommand_message.fin_vel)
clear_has_fin_vel();
::position_message* temp = fin_vel_;
fin_vel_ = NULL;
@@ -271,6 +310,7 @@ inline void RobotCommand_message::set_allocated_fin_vel(::position_message* fin_
} else {
clear_has_fin_vel();
}
+ // @@protoc_insertion_point(field_set_allocated:RobotCommand_message.fin_vel)
}
// required float maxSpeed = 3;
@@ -288,11 +328,13 @@ inline void RobotCommand_message::clear_maxspeed() {
clear_has_maxspeed();
}
inline float RobotCommand_message::maxspeed() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.maxSpeed)
return maxspeed_;
}
inline void RobotCommand_message::set_maxspeed(float value) {
set_has_maxspeed();
maxspeed_ = value;
+ // @@protoc_insertion_point(field_set:RobotCommand_message.maxSpeed)
}
// required float kickspeedx = 4;
@@ -310,11 +352,13 @@ inline void RobotCommand_message::clear_kickspeedx() {
clear_has_kickspeedx();
}
inline float RobotCommand_message::kickspeedx() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.kickspeedx)
return kickspeedx_;
}
inline void RobotCommand_message::set_kickspeedx(float value) {
set_has_kickspeedx();
kickspeedx_ = value;
+ // @@protoc_insertion_point(field_set:RobotCommand_message.kickspeedx)
}
// required float kickspeedz = 5;
@@ -332,11 +376,13 @@ inline void RobotCommand_message::clear_kickspeedz() {
clear_has_kickspeedz();
}
inline float RobotCommand_message::kickspeedz() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.kickspeedz)
return kickspeedz_;
}
inline void RobotCommand_message::set_kickspeedz(float value) {
set_has_kickspeedz();
kickspeedz_ = value;
+ // @@protoc_insertion_point(field_set:RobotCommand_message.kickspeedz)
}
// required bool useNav = 6;
@@ -354,11 +400,13 @@ inline void RobotCommand_message::clear_usenav() {
clear_has_usenav();
}
inline bool RobotCommand_message::usenav() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.useNav)
return usenav_;
}
inline void RobotCommand_message::set_usenav(bool value) {
set_has_usenav();
usenav_ = value;
+ // @@protoc_insertion_point(field_set:RobotCommand_message.useNav)
}
// required bool isBallObs = 7;
@@ -376,11 +424,13 @@ inline void RobotCommand_message::clear_isballobs() {
clear_has_isballobs();
}
inline bool RobotCommand_message::isballobs() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.isBallObs)
return isballobs_;
}
inline void RobotCommand_message::set_isballobs(bool value) {
set_has_isballobs();
isballobs_ = value;
+ // @@protoc_insertion_point(field_set:RobotCommand_message.isBallObs)
}
// required bool isKickObs = 8;
@@ -398,24 +448,19 @@ inline void RobotCommand_message::clear_iskickobs() {
clear_has_iskickobs();
}
inline bool RobotCommand_message::iskickobs() const {
+ // @@protoc_insertion_point(field_get:RobotCommand_message.isKickObs)
return iskickobs_;
}
inline void RobotCommand_message::set_iskickobs(bool value) {
set_has_iskickobs();
iskickobs_ = value;
+ // @@protoc_insertion_point(field_set:RobotCommand_message.isKickObs)
}
+#endif // !PROTOBUF_INLINE_NOT_IN_HEADERS
// @@protoc_insertion_point(namespace_scope)
-#ifndef SWIG
-namespace google {
-namespace protobuf {
-
-
-} // namespace google
-} // namespace protobuf
-#endif // SWIG
// @@protoc_insertion_point(global_scope)
diff --git a/src/proto/Robot_message.pb.cc b/src/proto/Robot_message.pb.cc
index 005b78b..43d2036 100644
--- a/src/proto/Robot_message.pb.cc
+++ b/src/proto/Robot_message.pb.cc
@@ -7,6 +7,7 @@
#include
#include
+#include
#include
#include
#include
@@ -15,27 +16,24 @@
#include
#include
// @@protoc_insertion_point(includes)
+class Robot_messageDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed {};
+Robot_messageDefaultTypeInternal _Robot_message_default_instance_;
namespace {
-const ::google::protobuf::Descriptor* Robot_message_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- Robot_message_reflection_ = NULL;
-const ::google::protobuf::EnumDescriptor* Robot_message_AgentStatus_descriptor_ = NULL;
-const ::google::protobuf::EnumDescriptor* Robot_message_AgentRegion_descriptor_ = NULL;
-const ::google::protobuf::EnumDescriptor* Robot_message_AgentRole_descriptor_ = NULL;
+::google::protobuf::Metadata file_level_metadata[1];
+const ::google::protobuf::EnumDescriptor* file_level_enum_descriptors[3];
} // namespace
-void protobuf_AssignDesc_Robot_5fmessage_2eproto() {
- protobuf_AddDesc_Robot_5fmessage_2eproto();
- const ::google::protobuf::FileDescriptor* file =
- ::google::protobuf::DescriptorPool::generated_pool()->FindFileByName(
- "Robot_message.proto");
- GOOGLE_CHECK(file != NULL);
- Robot_message_descriptor_ = file->message_type(0);
- static const int Robot_message_offsets_[7] = {
+const ::google::protobuf::uint32* protobuf_Offsets_Robot_5fmessage_2eproto() GOOGLE_ATTRIBUTE_COLD;
+const ::google::protobuf::uint32* protobuf_Offsets_Robot_5fmessage_2eproto() {
+ static const ::google::protobuf::uint32 offsets[] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Robot_message, _has_bits_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Robot_message, _internal_metadata_),
+ ~0u, // no _extensions_
+ ~0u, // no _oneof_case_
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Robot_message, isvalid_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Robot_message, position_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Robot_message, velocity_),
@@ -43,96 +41,123 @@ void protobuf_AssignDesc_Robot_5fmessage_2eproto() {
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Robot_message, role_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Robot_message, region_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Robot_message, rc_),
+ 3,
+ 0,
+ 1,
+ 5,
+ 6,
+ 4,
+ 2,
};
- Robot_message_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- Robot_message_descriptor_,
- Robot_message::default_instance_,
- Robot_message_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Robot_message, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(Robot_message, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(Robot_message));
- Robot_message_AgentStatus_descriptor_ = Robot_message_descriptor_->enum_type(0);
- Robot_message_AgentRegion_descriptor_ = Robot_message_descriptor_->enum_type(1);
- Robot_message_AgentRole_descriptor_ = Robot_message_descriptor_->enum_type(2);
+ return offsets;
}
+static const ::google::protobuf::internal::MigrationSchema schemas[] = {
+ { 0, 11, sizeof(Robot_message)},
+};
+
+static const ::google::protobuf::internal::DefaultInstanceData file_default_instances[] = {
+ {reinterpret_cast(&_Robot_message_default_instance_), NULL},
+};
+
namespace {
-GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AssignDescriptors_once_);
-inline void protobuf_AssignDescriptorsOnce() {
- ::google::protobuf::GoogleOnceInit(&protobuf_AssignDescriptors_once_,
- &protobuf_AssignDesc_Robot_5fmessage_2eproto);
+void protobuf_AssignDescriptors() {
+ protobuf_AddDesc_Robot_5fmessage_2eproto();
+ ::google::protobuf::MessageFactory* factory = NULL;
+ AssignDescriptors(
+ "Robot_message.proto", schemas, file_default_instances, protobuf_Offsets_Robot_5fmessage_2eproto(), factory,
+ file_level_metadata, file_level_enum_descriptors, NULL);
}
+void protobuf_AssignDescriptorsOnce() {
+ static GOOGLE_PROTOBUF_DECLARE_ONCE(once);
+ ::google::protobuf::GoogleOnceInit(&once, &protobuf_AssignDescriptors);
+}
+
+void protobuf_RegisterTypes(const ::std::string&) GOOGLE_ATTRIBUTE_COLD;
void protobuf_RegisterTypes(const ::std::string&) {
protobuf_AssignDescriptorsOnce();
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- Robot_message_descriptor_, &Robot_message::default_instance());
+ ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 1);
}
} // namespace
void protobuf_ShutdownFile_Robot_5fmessage_2eproto() {
- delete Robot_message::default_instance_;
- delete Robot_message_reflection_;
+ _Robot_message_default_instance_.Shutdown();
+ delete file_level_metadata[0].reflection;
}
-void protobuf_AddDesc_Robot_5fmessage_2eproto() {
- static bool already_here = false;
- if (already_here) return;
- already_here = true;
+void protobuf_InitDefaults_Robot_5fmessage_2eproto_impl() {
GOOGLE_PROTOBUF_VERIFY_VERSION;
- ::protobuf_AddDesc_position_5fmessage_2eproto();
- ::protobuf_AddDesc_RobotCommand_5fmessage_2eproto();
+ ::protobuf_InitDefaults_position_5fmessage_2eproto();
+ ::protobuf_InitDefaults_RobotCommand_5fmessage_2eproto();
+ ::google::protobuf::internal::InitProtobufDefaults();
+ _Robot_message_default_instance_.DefaultConstruct();
+ _Robot_message_default_instance_.get_mutable()->position_ = const_cast< ::position_message*>(
+ ::position_message::internal_default_instance());
+ _Robot_message_default_instance_.get_mutable()->velocity_ = const_cast< ::position_message*>(
+ ::position_message::internal_default_instance());
+ _Robot_message_default_instance_.get_mutable()->rc_ = const_cast< ::RobotCommand_message*>(
+ ::RobotCommand_message::internal_default_instance());
+}
+
+void protobuf_InitDefaults_Robot_5fmessage_2eproto() {
+ static GOOGLE_PROTOBUF_DECLARE_ONCE(once);
+ ::google::protobuf::GoogleOnceInit(&once, &protobuf_InitDefaults_Robot_5fmessage_2eproto_impl);
+}
+void protobuf_AddDesc_Robot_5fmessage_2eproto_impl() {
+ protobuf_InitDefaults_Robot_5fmessage_2eproto();
+ static const char descriptor[] = {
+ "\n\023Robot_message.proto\032\026position_message."
+ "proto\032\032RobotCommand_message.proto\"\341\005\n\rRo"
+ "bot_message\022\017\n\007isValid\030\001 \002(\010\022#\n\010position"
+ "\030\002 \002(\0132\021.position_message\022#\n\010velocity\030\003 "
+ "\002(\0132\021.position_message\022*\n\006status\030\004 \001(\0162\032"
+ ".Robot_message.AgentStatus\022&\n\004role\030\005 \001(\016"
+ "2\030.Robot_message.AgentRole\022*\n\006region\030\006 \001"
+ "(\0162\032.Robot_message.AgentRegion\022!\n\002rc\030\007 \001"
+ "(\0132\025.RobotCommand_message\"\211\001\n\013AgentStatu"
+ "s\022\010\n\004Idle\020\001\022\013\n\007Passing\020\002\022\013\n\007Kicking\020\003\022\013\n"
+ "\007Chiping\020\004\022\021\n\rFollowingBall\020\005\022\020\n\014Blockin"
+ "gBall\020\006\022\021\n\rBlockingRobot\020\007\022\021\n\rRecievingP"
+ "ass\020\010\"<\n\013AgentRegion\022\014\n\010NoRegion\020\025\022\010\n\004Le"
+ "ft\020\026\022\n\n\006Center\020\027\022\t\n\005Right\020\030\"\207\002\n\tAgentRol"
+ "e\022\n\n\006NoRole\020\037\022\n\n\006ArcMid\020 \022\013\n\007ArcLeft\020!\022\014"
+ "\n\010ArcRight\020\"\022\025\n\021FixedPositionLeft\020#\022\026\n\022F"
+ "ixedPositionRight\020$\022\024\n\020FixedPositionMid\020"
+ "%\022\020\n\014AttackerLeft\020&\022\021\n\rAttackerRight\020\'\022\017"
+ "\n\013AttackerMid\020(\022\013\n\007Blocker\020)\022\020\n\014Defender"
+ "Left\020*\022\021\n\rDefenderRight\020+\022\017\n\013DefenderMid"
+ "\020,\022\t\n\005Golie\020-"
+ };
::google::protobuf::DescriptorPool::InternalAddGeneratedFile(
- "\n\023Robot_message.proto\032\026position_message."
- "proto\032\032RobotCommand_message.proto\"\341\005\n\rRo"
- "bot_message\022\017\n\007isValid\030\001 \002(\010\022#\n\010position"
- "\030\002 \002(\0132\021.position_message\022#\n\010velocity\030\003 "
- "\002(\0132\021.position_message\022*\n\006status\030\004 \001(\0162\032"
- ".Robot_message.AgentStatus\022&\n\004role\030\005 \001(\016"
- "2\030.Robot_message.AgentRole\022*\n\006region\030\006 \001"
- "(\0162\032.Robot_message.AgentRegion\022!\n\002rc\030\007 \001"
- "(\0132\025.RobotCommand_message\"\211\001\n\013AgentStatu"
- "s\022\010\n\004Idle\020\001\022\013\n\007Passing\020\002\022\013\n\007Kicking\020\003\022\013\n"
- "\007Chiping\020\004\022\021\n\rFollowingBall\020\005\022\020\n\014Blockin"
- "gBall\020\006\022\021\n\rBlockingRobot\020\007\022\021\n\rRecievingP"
- "ass\020\010\"<\n\013AgentRegion\022\014\n\010NoRegion\020\025\022\010\n\004Le"
- "ft\020\026\022\n\n\006Center\020\027\022\t\n\005Right\020\030\"\207\002\n\tAgentRol"
- "e\022\n\n\006NoRole\020\037\022\n\n\006ArcMid\020 \022\013\n\007ArcLeft\020!\022\014"
- "\n\010ArcRight\020\"\022\025\n\021FixedPositionLeft\020#\022\026\n\022F"
- "ixedPositionRight\020$\022\024\n\020FixedPositionMid\020"
- "%\022\020\n\014AttackerLeft\020&\022\021\n\rAttackerRight\020\'\022\017"
- "\n\013AttackerMid\020(\022\013\n\007Blocker\020)\022\020\n\014Defender"
- "Left\020*\022\021\n\rDefenderRight\020+\022\017\n\013DefenderMid"
- "\020,\022\t\n\005Golie\020-", 813);
+ descriptor, 813);
::google::protobuf::MessageFactory::InternalRegisterGeneratedFile(
"Robot_message.proto", &protobuf_RegisterTypes);
- Robot_message::default_instance_ = new Robot_message();
- Robot_message::default_instance_->InitAsDefaultInstance();
+ ::protobuf_AddDesc_position_5fmessage_2eproto();
+ ::protobuf_AddDesc_RobotCommand_5fmessage_2eproto();
::google::protobuf::internal::OnShutdown(&protobuf_ShutdownFile_Robot_5fmessage_2eproto);
}
+GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AddDesc_Robot_5fmessage_2eproto_once_);
+void protobuf_AddDesc_Robot_5fmessage_2eproto() {
+ ::google::protobuf::GoogleOnceInit(&protobuf_AddDesc_Robot_5fmessage_2eproto_once_,
+ &protobuf_AddDesc_Robot_5fmessage_2eproto_impl);
+}
// Force AddDescriptors() to be called at static initialization time.
struct StaticDescriptorInitializer_Robot_5fmessage_2eproto {
StaticDescriptorInitializer_Robot_5fmessage_2eproto() {
protobuf_AddDesc_Robot_5fmessage_2eproto();
}
} static_descriptor_initializer_Robot_5fmessage_2eproto_;
-
-// ===================================================================
-
const ::google::protobuf::EnumDescriptor* Robot_message_AgentStatus_descriptor() {
protobuf_AssignDescriptorsOnce();
- return Robot_message_AgentStatus_descriptor_;
+ return file_level_enum_descriptors[0];
}
bool Robot_message_AgentStatus_IsValid(int value) {
- switch(value) {
+ switch (value) {
case 1:
case 2:
case 3:
@@ -147,7 +172,7 @@ bool Robot_message_AgentStatus_IsValid(int value) {
}
}
-#ifndef _MSC_VER
+#if !defined(_MSC_VER) || _MSC_VER >= 1900
const Robot_message_AgentStatus Robot_message::Idle;
const Robot_message_AgentStatus Robot_message::Passing;
const Robot_message_AgentStatus Robot_message::Kicking;
@@ -159,13 +184,13 @@ const Robot_message_AgentStatus Robot_message::RecievingPass;
const Robot_message_AgentStatus Robot_message::AgentStatus_MIN;
const Robot_message_AgentStatus Robot_message::AgentStatus_MAX;
const int Robot_message::AgentStatus_ARRAYSIZE;
-#endif // _MSC_VER
+#endif // !defined(_MSC_VER) || _MSC_VER >= 1900
const ::google::protobuf::EnumDescriptor* Robot_message_AgentRegion_descriptor() {
protobuf_AssignDescriptorsOnce();
- return Robot_message_AgentRegion_descriptor_;
+ return file_level_enum_descriptors[1];
}
bool Robot_message_AgentRegion_IsValid(int value) {
- switch(value) {
+ switch (value) {
case 21:
case 22:
case 23:
@@ -176,7 +201,7 @@ bool Robot_message_AgentRegion_IsValid(int value) {
}
}
-#ifndef _MSC_VER
+#if !defined(_MSC_VER) || _MSC_VER >= 1900
const Robot_message_AgentRegion Robot_message::NoRegion;
const Robot_message_AgentRegion Robot_message::Left;
const Robot_message_AgentRegion Robot_message::Center;
@@ -184,13 +209,13 @@ const Robot_message_AgentRegion Robot_message::Right;
const Robot_message_AgentRegion Robot_message::AgentRegion_MIN;
const Robot_message_AgentRegion Robot_message::AgentRegion_MAX;
const int Robot_message::AgentRegion_ARRAYSIZE;
-#endif // _MSC_VER
+#endif // !defined(_MSC_VER) || _MSC_VER >= 1900
const ::google::protobuf::EnumDescriptor* Robot_message_AgentRole_descriptor() {
protobuf_AssignDescriptorsOnce();
- return Robot_message_AgentRole_descriptor_;
+ return file_level_enum_descriptors[2];
}
bool Robot_message_AgentRole_IsValid(int value) {
- switch(value) {
+ switch (value) {
case 31:
case 32:
case 33:
@@ -212,7 +237,7 @@ bool Robot_message_AgentRole_IsValid(int value) {
}
}
-#ifndef _MSC_VER
+#if !defined(_MSC_VER) || _MSC_VER >= 1900
const Robot_message_AgentRole Robot_message::NoRole;
const Robot_message_AgentRole Robot_message::ArcMid;
const Robot_message_AgentRole Robot_message::ArcLeft;
@@ -231,8 +256,11 @@ const Robot_message_AgentRole Robot_message::Golie;
const Robot_message_AgentRole Robot_message::AgentRole_MIN;
const Robot_message_AgentRole Robot_message::AgentRole_MAX;
const int Robot_message::AgentRole_ARRAYSIZE;
-#endif // _MSC_VER
-#ifndef _MSC_VER
+#endif // !defined(_MSC_VER) || _MSC_VER >= 1900
+
+// ===================================================================
+
+#if !defined(_MSC_VER) || _MSC_VER >= 1900
const int Robot_message::kIsValidFieldNumber;
const int Robot_message::kPositionFieldNumber;
const int Robot_message::kVelocityFieldNumber;
@@ -240,45 +268,65 @@ const int Robot_message::kStatusFieldNumber;
const int Robot_message::kRoleFieldNumber;
const int Robot_message::kRegionFieldNumber;
const int Robot_message::kRcFieldNumber;
-#endif // !_MSC_VER
+#endif // !defined(_MSC_VER) || _MSC_VER >= 1900
Robot_message::Robot_message()
- : ::google::protobuf::Message() {
+ : ::google::protobuf::Message(), _internal_metadata_(NULL) {
+ if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) {
+ protobuf_InitDefaults_Robot_5fmessage_2eproto();
+ }
SharedCtor();
+ // @@protoc_insertion_point(constructor:Robot_message)
}
-
-void Robot_message::InitAsDefaultInstance() {
- position_ = const_cast< ::position_message*>(&::position_message::default_instance());
- velocity_ = const_cast< ::position_message*>(&::position_message::default_instance());
- rc_ = const_cast< ::RobotCommand_message*>(&::RobotCommand_message::default_instance());
-}
-
Robot_message::Robot_message(const Robot_message& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
+ : ::google::protobuf::Message(),
+ _internal_metadata_(NULL),
+ _has_bits_(from._has_bits_),
+ _cached_size_(0) {
+ _internal_metadata_.MergeFrom(from._internal_metadata_);
+ if (from.has_position()) {
+ position_ = new ::position_message(*from.position_);
+ } else {
+ position_ = NULL;
+ }
+ if (from.has_velocity()) {
+ velocity_ = new ::position_message(*from.velocity_);
+ } else {
+ velocity_ = NULL;
+ }
+ if (from.has_rc()) {
+ rc_ = new ::RobotCommand_message(*from.rc_);
+ } else {
+ rc_ = NULL;
+ }
+ ::memcpy(&isvalid_, &from.isvalid_,
+ reinterpret_cast(&role_) -
+ reinterpret_cast(&isvalid_) + sizeof(role_));
+ // @@protoc_insertion_point(copy_constructor:Robot_message)
}
void Robot_message::SharedCtor() {
_cached_size_ = 0;
- isvalid_ = false;
- position_ = NULL;
- velocity_ = NULL;
+ ::memset(&position_, 0, reinterpret_cast(&isvalid_) -
+ reinterpret_cast(&position_) + sizeof(isvalid_));
+ region_ = 21;
status_ = 1;
role_ = 31;
- region_ = 21;
- rc_ = NULL;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
}
Robot_message::~Robot_message() {
+ // @@protoc_insertion_point(destructor:Robot_message)
SharedDtor();
}
void Robot_message::SharedDtor() {
- if (this != default_instance_) {
+ if (this != internal_default_instance()) {
delete position_;
+ }
+ if (this != internal_default_instance()) {
delete velocity_;
+ }
+ if (this != internal_default_instance()) {
delete rc_;
}
}
@@ -290,94 +338,96 @@ void Robot_message::SetCachedSize(int size) const {
}
const ::google::protobuf::Descriptor* Robot_message::descriptor() {
protobuf_AssignDescriptorsOnce();
- return Robot_message_descriptor_;
+ return file_level_metadata[0].descriptor;
}
const Robot_message& Robot_message::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_Robot_5fmessage_2eproto();
- return *default_instance_;
+ protobuf_InitDefaults_Robot_5fmessage_2eproto();
+ return *internal_default_instance();
}
-Robot_message* Robot_message::default_instance_ = NULL;
-
-Robot_message* Robot_message::New() const {
- return new Robot_message;
+Robot_message* Robot_message::New(::google::protobuf::Arena* arena) const {
+ Robot_message* n = new Robot_message;
+ if (arena != NULL) {
+ arena->Own(n);
+ }
+ return n;
}
void Robot_message::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- isvalid_ = false;
+// @@protoc_insertion_point(message_clear_start:Robot_message)
+ if (_has_bits_[0 / 32] & 7u) {
if (has_position()) {
- if (position_ != NULL) position_->::position_message::Clear();
+ GOOGLE_DCHECK(position_ != NULL);
+ position_->::position_message::Clear();
}
if (has_velocity()) {
- if (velocity_ != NULL) velocity_->::position_message::Clear();
+ GOOGLE_DCHECK(velocity_ != NULL);
+ velocity_->::position_message::Clear();
}
- status_ = 1;
- role_ = 31;
- region_ = 21;
if (has_rc()) {
- if (rc_ != NULL) rc_->::RobotCommand_message::Clear();
+ GOOGLE_DCHECK(rc_ != NULL);
+ rc_->::RobotCommand_message::Clear();
}
}
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
+ if (_has_bits_[0 / 32] & 120u) {
+ isvalid_ = false;
+ region_ = 21;
+ status_ = 1;
+ role_ = 31;
+ }
+ _has_bits_.Clear();
+ _internal_metadata_.Clear();
}
bool Robot_message::MergePartialFromCodedStream(
::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure
::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
+ // @@protoc_insertion_point(parse_start:Robot_message)
+ for (;;) {
+ ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u);
+ tag = p.first;
+ if (!p.second) goto handle_unusual;
switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
// required bool isValid = 1;
case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ if (tag == 8u) {
+ set_has_isvalid();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>(
input, &isvalid_)));
- set_has_isvalid();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(18)) goto parse_position;
break;
}
// required .position_message position = 2;
case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_position:
+ if (tag == 18u) {
DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
input, mutable_position()));
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(26)) goto parse_velocity;
break;
}
// required .position_message velocity = 3;
case 3: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_velocity:
+ if (tag == 26u) {
DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
input, mutable_velocity()));
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(32)) goto parse_status;
break;
}
// optional .Robot_message.AgentStatus status = 4;
case 4: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_status:
+ if (tag == 32u) {
int value;
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>(
@@ -388,17 +438,14 @@ bool Robot_message::MergePartialFromCodedStream(
mutable_unknown_fields()->AddVarint(4, value);
}
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(40)) goto parse_role;
break;
}
// optional .Robot_message.AgentRole role = 5;
case 5: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_role:
+ if (tag == 40u) {
int value;
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>(
@@ -409,17 +456,14 @@ bool Robot_message::MergePartialFromCodedStream(
mutable_unknown_fields()->AddVarint(5, value);
}
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(48)) goto parse_region;
break;
}
// optional .Robot_message.AgentRegion region = 6;
case 6: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_region:
+ if (tag == 48u) {
int value;
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
int, ::google::protobuf::internal::WireFormatLite::TYPE_ENUM>(
@@ -430,31 +474,28 @@ bool Robot_message::MergePartialFromCodedStream(
mutable_unknown_fields()->AddVarint(6, value);
}
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(58)) goto parse_rc;
break;
}
// optional .RobotCommand_message rc = 7;
case 7: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_LENGTH_DELIMITED) {
- parse_rc:
+ if (tag == 58u) {
DO_(::google::protobuf::internal::WireFormatLite::ReadMessageNoVirtual(
input, mutable_rc()));
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectAtEnd()) return true;
break;
}
default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ handle_unusual:
+ if (tag == 0 ||
+ ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
+ goto success;
}
DO_(::google::protobuf::internal::WireFormat::SkipField(
input, tag, mutable_unknown_fields()));
@@ -462,12 +503,18 @@ bool Robot_message::MergePartialFromCodedStream(
}
}
}
+success:
+ // @@protoc_insertion_point(parse_success:Robot_message)
return true;
+failure:
+ // @@protoc_insertion_point(parse_failure:Robot_message)
+ return false;
#undef DO_
}
void Robot_message::SerializeWithCachedSizes(
::google::protobuf::io::CodedOutputStream* output) const {
+ // @@protoc_insertion_point(serialize_start:Robot_message)
// required bool isValid = 1;
if (has_isvalid()) {
::google::protobuf::internal::WireFormatLite::WriteBool(1, this->isvalid(), output);
@@ -476,13 +523,13 @@ void Robot_message::SerializeWithCachedSizes(
// required .position_message position = 2;
if (has_position()) {
::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 2, this->position(), output);
+ 2, *this->position_, output);
}
// required .position_message velocity = 3;
if (has_velocity()) {
::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 3, this->velocity(), output);
+ 3, *this->velocity_, output);
}
// optional .Robot_message.AgentStatus status = 4;
@@ -506,17 +553,20 @@ void Robot_message::SerializeWithCachedSizes(
// optional .RobotCommand_message rc = 7;
if (has_rc()) {
::google::protobuf::internal::WireFormatLite::WriteMessageMaybeToArray(
- 7, this->rc(), output);
+ 7, *this->rc_, output);
}
- if (!unknown_fields().empty()) {
+ if (_internal_metadata_.have_unknown_fields()) {
::google::protobuf::internal::WireFormat::SerializeUnknownFields(
unknown_fields(), output);
}
+ // @@protoc_insertion_point(serialize_end:Robot_message)
}
-::google::protobuf::uint8* Robot_message::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
+::google::protobuf::uint8* Robot_message::InternalSerializeWithCachedSizesToArray(
+ bool deterministic, ::google::protobuf::uint8* target) const {
+ (void)deterministic; // Unused
+ // @@protoc_insertion_point(serialize_to_array_start:Robot_message)
// required bool isValid = 1;
if (has_isvalid()) {
target = ::google::protobuf::internal::WireFormatLite::WriteBoolToArray(1, this->isvalid(), target);
@@ -525,15 +575,15 @@ ::google::protobuf::uint8* Robot_message::SerializeWithCachedSizesToArray(
// required .position_message position = 2;
if (has_position()) {
target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 2, this->position(), target);
+ InternalWriteMessageNoVirtualToArray(
+ 2, *this->position_, false, target);
}
// required .position_message velocity = 3;
if (has_velocity()) {
target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 3, this->velocity(), target);
+ InternalWriteMessageNoVirtualToArray(
+ 3, *this->velocity_, false, target);
}
// optional .Robot_message.AgentStatus status = 4;
@@ -557,38 +607,81 @@ ::google::protobuf::uint8* Robot_message::SerializeWithCachedSizesToArray(
// optional .RobotCommand_message rc = 7;
if (has_rc()) {
target = ::google::protobuf::internal::WireFormatLite::
- WriteMessageNoVirtualToArray(
- 7, this->rc(), target);
+ InternalWriteMessageNoVirtualToArray(
+ 7, *this->rc_, false, target);
}
- if (!unknown_fields().empty()) {
+ if (_internal_metadata_.have_unknown_fields()) {
target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
unknown_fields(), target);
}
+ // @@protoc_insertion_point(serialize_to_array_end:Robot_message)
return target;
}
-int Robot_message::ByteSize() const {
- int total_size = 0;
+size_t Robot_message::RequiredFieldsByteSizeFallback() const {
+// @@protoc_insertion_point(required_fields_byte_size_fallback_start:Robot_message)
+ size_t total_size = 0;
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (has_position()) {
+ // required .position_message position = 2;
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ *this->position_);
+ }
+
+ if (has_velocity()) {
+ // required .position_message velocity = 3;
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ *this->velocity_);
+ }
+
+ if (has_isvalid()) {
// required bool isValid = 1;
- if (has_isvalid()) {
- total_size += 1 + 1;
- }
+ total_size += 1 + 1;
+ }
+
+ return total_size;
+}
+size_t Robot_message::ByteSizeLong() const {
+// @@protoc_insertion_point(message_byte_size_start:Robot_message)
+ size_t total_size = 0;
+ if (_internal_metadata_.have_unknown_fields()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ if (((_has_bits_[0] & 0x0000000b) ^ 0x0000000b) == 0) { // All required fields are present.
// required .position_message position = 2;
- if (has_position()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->position());
- }
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ *this->position_);
// required .position_message velocity = 3;
- if (has_velocity()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ *this->velocity_);
+
+ // required bool isValid = 1;
+ total_size += 1 + 1;
+
+ } else {
+ total_size += RequiredFieldsByteSizeFallback();
+ }
+ // optional .RobotCommand_message rc = 7;
+ if (has_rc()) {
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
+ *this->rc_);
+ }
+
+ if (_has_bits_[0 / 32] & 112u) {
+ // optional .Robot_message.AgentRegion region = 6;
+ if (has_region()) {
total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->velocity());
+ ::google::protobuf::internal::WireFormatLite::EnumSize(this->region());
}
// optional .Robot_message.AgentStatus status = 4;
@@ -603,121 +696,346 @@ int Robot_message::ByteSize() const {
::google::protobuf::internal::WireFormatLite::EnumSize(this->role());
}
- // optional .Robot_message.AgentRegion region = 6;
- if (has_region()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::EnumSize(this->region());
- }
-
- // optional .RobotCommand_message rc = 7;
- if (has_rc()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::MessageSizeNoVirtual(
- this->rc());
- }
-
- }
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
}
+ int cached_size = ::google::protobuf::internal::ToCachedSize(total_size);
GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
+ _cached_size_ = cached_size;
GOOGLE_SAFE_CONCURRENT_WRITES_END();
return total_size;
}
void Robot_message::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
+// @@protoc_insertion_point(generalized_merge_from_start:Robot_message)
+ GOOGLE_DCHECK_NE(&from, this);
const Robot_message* source =
- ::google::protobuf::internal::dynamic_cast_if_available(
- &from);
+ ::google::protobuf::internal::DynamicCastToGenerated(
+ &from);
if (source == NULL) {
+ // @@protoc_insertion_point(generalized_merge_from_cast_fail:Robot_message)
::google::protobuf::internal::ReflectionOps::Merge(from, this);
} else {
+ // @@protoc_insertion_point(generalized_merge_from_cast_success:Robot_message)
MergeFrom(*source);
}
}
void Robot_message::MergeFrom(const Robot_message& from) {
- GOOGLE_CHECK_NE(&from, this);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- if (from.has_isvalid()) {
- set_isvalid(from.isvalid());
- }
+// @@protoc_insertion_point(class_specific_merge_from_start:Robot_message)
+ GOOGLE_DCHECK_NE(&from, this);
+ _internal_metadata_.MergeFrom(from._internal_metadata_);
+ if (from._has_bits_[0 / 32] & 127u) {
if (from.has_position()) {
mutable_position()->::position_message::MergeFrom(from.position());
}
if (from.has_velocity()) {
mutable_velocity()->::position_message::MergeFrom(from.velocity());
}
- if (from.has_status()) {
- set_status(from.status());
+ if (from.has_rc()) {
+ mutable_rc()->::RobotCommand_message::MergeFrom(from.rc());
}
- if (from.has_role()) {
- set_role(from.role());
+ if (from.has_isvalid()) {
+ set_isvalid(from.isvalid());
}
if (from.has_region()) {
set_region(from.region());
}
- if (from.has_rc()) {
- mutable_rc()->::RobotCommand_message::MergeFrom(from.rc());
+ if (from.has_status()) {
+ set_status(from.status());
+ }
+ if (from.has_role()) {
+ set_role(from.role());
}
}
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
}
void Robot_message::CopyFrom(const ::google::protobuf::Message& from) {
+// @@protoc_insertion_point(generalized_copy_from_start:Robot_message)
if (&from == this) return;
Clear();
MergeFrom(from);
}
void Robot_message::CopyFrom(const Robot_message& from) {
+// @@protoc_insertion_point(class_specific_copy_from_start:Robot_message)
if (&from == this) return;
Clear();
MergeFrom(from);
}
bool Robot_message::IsInitialized() const {
- if ((_has_bits_[0] & 0x00000007) != 0x00000007) return false;
-
+ if ((_has_bits_[0] & 0x0000000b) != 0x0000000b) return false;
if (has_position()) {
- if (!this->position().IsInitialized()) return false;
+ if (!this->position_->IsInitialized()) return false;
}
if (has_velocity()) {
- if (!this->velocity().IsInitialized()) return false;
+ if (!this->velocity_->IsInitialized()) return false;
}
if (has_rc()) {
- if (!this->rc().IsInitialized()) return false;
+ if (!this->rc_->IsInitialized()) return false;
}
return true;
}
void Robot_message::Swap(Robot_message* other) {
- if (other != this) {
- std::swap(isvalid_, other->isvalid_);
- std::swap(position_, other->position_);
- std::swap(velocity_, other->velocity_);
- std::swap(status_, other->status_);
- std::swap(role_, other->role_);
- std::swap(region_, other->region_);
- std::swap(rc_, other->rc_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
+ if (other == this) return;
+ InternalSwap(other);
+}
+void Robot_message::InternalSwap(Robot_message* other) {
+ std::swap(position_, other->position_);
+ std::swap(velocity_, other->velocity_);
+ std::swap(rc_, other->rc_);
+ std::swap(isvalid_, other->isvalid_);
+ std::swap(region_, other->region_);
+ std::swap(status_, other->status_);
+ std::swap(role_, other->role_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _internal_metadata_.Swap(&other->_internal_metadata_);
+ std::swap(_cached_size_, other->_cached_size_);
}
::google::protobuf::Metadata Robot_message::GetMetadata() const {
protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = Robot_message_descriptor_;
- metadata.reflection = Robot_message_reflection_;
- return metadata;
+ return file_level_metadata[0];
+}
+
+#if PROTOBUF_INLINE_NOT_IN_HEADERS
+// Robot_message
+
+// required bool isValid = 1;
+bool Robot_message::has_isvalid() const {
+ return (_has_bits_[0] & 0x00000008u) != 0;
+}
+void Robot_message::set_has_isvalid() {
+ _has_bits_[0] |= 0x00000008u;
+}
+void Robot_message::clear_has_isvalid() {
+ _has_bits_[0] &= ~0x00000008u;
+}
+void Robot_message::clear_isvalid() {
+ isvalid_ = false;
+ clear_has_isvalid();
+}
+bool Robot_message::isvalid() const {
+ // @@protoc_insertion_point(field_get:Robot_message.isValid)
+ return isvalid_;
+}
+void Robot_message::set_isvalid(bool value) {
+ set_has_isvalid();
+ isvalid_ = value;
+ // @@protoc_insertion_point(field_set:Robot_message.isValid)
+}
+
+// required .position_message position = 2;
+bool Robot_message::has_position() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+void Robot_message::set_has_position() {
+ _has_bits_[0] |= 0x00000001u;
+}
+void Robot_message::clear_has_position() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+void Robot_message::clear_position() {
+ if (position_ != NULL) position_->::position_message::Clear();
+ clear_has_position();
+}
+const ::position_message& Robot_message::position() const {
+ // @@protoc_insertion_point(field_get:Robot_message.position)
+ return position_ != NULL ? *position_
+ : *::position_message::internal_default_instance();
+}
+::position_message* Robot_message::mutable_position() {
+ set_has_position();
+ if (position_ == NULL) {
+ position_ = new ::position_message;
+ }
+ // @@protoc_insertion_point(field_mutable:Robot_message.position)
+ return position_;
+}
+::position_message* Robot_message::release_position() {
+ // @@protoc_insertion_point(field_release:Robot_message.position)
+ clear_has_position();
+ ::position_message* temp = position_;
+ position_ = NULL;
+ return temp;
+}
+void Robot_message::set_allocated_position(::position_message* position) {
+ delete position_;
+ position_ = position;
+ if (position) {
+ set_has_position();
+ } else {
+ clear_has_position();
+ }
+ // @@protoc_insertion_point(field_set_allocated:Robot_message.position)
+}
+
+// required .position_message velocity = 3;
+bool Robot_message::has_velocity() const {
+ return (_has_bits_[0] & 0x00000002u) != 0;
+}
+void Robot_message::set_has_velocity() {
+ _has_bits_[0] |= 0x00000002u;
+}
+void Robot_message::clear_has_velocity() {
+ _has_bits_[0] &= ~0x00000002u;
+}
+void Robot_message::clear_velocity() {
+ if (velocity_ != NULL) velocity_->::position_message::Clear();
+ clear_has_velocity();
+}
+const ::position_message& Robot_message::velocity() const {
+ // @@protoc_insertion_point(field_get:Robot_message.velocity)
+ return velocity_ != NULL ? *velocity_
+ : *::position_message::internal_default_instance();
+}
+::position_message* Robot_message::mutable_velocity() {
+ set_has_velocity();
+ if (velocity_ == NULL) {
+ velocity_ = new ::position_message;
+ }
+ // @@protoc_insertion_point(field_mutable:Robot_message.velocity)
+ return velocity_;
+}
+::position_message* Robot_message::release_velocity() {
+ // @@protoc_insertion_point(field_release:Robot_message.velocity)
+ clear_has_velocity();
+ ::position_message* temp = velocity_;
+ velocity_ = NULL;
+ return temp;
+}
+void Robot_message::set_allocated_velocity(::position_message* velocity) {
+ delete velocity_;
+ velocity_ = velocity;
+ if (velocity) {
+ set_has_velocity();
+ } else {
+ clear_has_velocity();
+ }
+ // @@protoc_insertion_point(field_set_allocated:Robot_message.velocity)
+}
+
+// optional .Robot_message.AgentStatus status = 4;
+bool Robot_message::has_status() const {
+ return (_has_bits_[0] & 0x00000020u) != 0;
+}
+void Robot_message::set_has_status() {
+ _has_bits_[0] |= 0x00000020u;
+}
+void Robot_message::clear_has_status() {
+ _has_bits_[0] &= ~0x00000020u;
+}
+void Robot_message::clear_status() {
+ status_ = 1;
+ clear_has_status();
+}
+::Robot_message_AgentStatus Robot_message::status() const {
+ // @@protoc_insertion_point(field_get:Robot_message.status)
+ return static_cast< ::Robot_message_AgentStatus >(status_);
+}
+void Robot_message::set_status(::Robot_message_AgentStatus value) {
+ assert(::Robot_message_AgentStatus_IsValid(value));
+ set_has_status();
+ status_ = value;
+ // @@protoc_insertion_point(field_set:Robot_message.status)
+}
+
+// optional .Robot_message.AgentRole role = 5;
+bool Robot_message::has_role() const {
+ return (_has_bits_[0] & 0x00000040u) != 0;
+}
+void Robot_message::set_has_role() {
+ _has_bits_[0] |= 0x00000040u;
+}
+void Robot_message::clear_has_role() {
+ _has_bits_[0] &= ~0x00000040u;
+}
+void Robot_message::clear_role() {
+ role_ = 31;
+ clear_has_role();
+}
+::Robot_message_AgentRole Robot_message::role() const {
+ // @@protoc_insertion_point(field_get:Robot_message.role)
+ return static_cast< ::Robot_message_AgentRole >(role_);
+}
+void Robot_message::set_role(::Robot_message_AgentRole value) {
+ assert(::Robot_message_AgentRole_IsValid(value));
+ set_has_role();
+ role_ = value;
+ // @@protoc_insertion_point(field_set:Robot_message.role)
+}
+
+// optional .Robot_message.AgentRegion region = 6;
+bool Robot_message::has_region() const {
+ return (_has_bits_[0] & 0x00000010u) != 0;
+}
+void Robot_message::set_has_region() {
+ _has_bits_[0] |= 0x00000010u;
+}
+void Robot_message::clear_has_region() {
+ _has_bits_[0] &= ~0x00000010u;
+}
+void Robot_message::clear_region() {
+ region_ = 21;
+ clear_has_region();
+}
+::Robot_message_AgentRegion Robot_message::region() const {
+ // @@protoc_insertion_point(field_get:Robot_message.region)
+ return static_cast< ::Robot_message_AgentRegion >(region_);
+}
+void Robot_message::set_region(::Robot_message_AgentRegion value) {
+ assert(::Robot_message_AgentRegion_IsValid(value));
+ set_has_region();
+ region_ = value;
+ // @@protoc_insertion_point(field_set:Robot_message.region)
+}
+
+// optional .RobotCommand_message rc = 7;
+bool Robot_message::has_rc() const {
+ return (_has_bits_[0] & 0x00000004u) != 0;
+}
+void Robot_message::set_has_rc() {
+ _has_bits_[0] |= 0x00000004u;
+}
+void Robot_message::clear_has_rc() {
+ _has_bits_[0] &= ~0x00000004u;
+}
+void Robot_message::clear_rc() {
+ if (rc_ != NULL) rc_->::RobotCommand_message::Clear();
+ clear_has_rc();
+}
+const ::RobotCommand_message& Robot_message::rc() const {
+ // @@protoc_insertion_point(field_get:Robot_message.rc)
+ return rc_ != NULL ? *rc_
+ : *::RobotCommand_message::internal_default_instance();
+}
+::RobotCommand_message* Robot_message::mutable_rc() {
+ set_has_rc();
+ if (rc_ == NULL) {
+ rc_ = new ::RobotCommand_message;
+ }
+ // @@protoc_insertion_point(field_mutable:Robot_message.rc)
+ return rc_;
+}
+::RobotCommand_message* Robot_message::release_rc() {
+ // @@protoc_insertion_point(field_release:Robot_message.rc)
+ clear_has_rc();
+ ::RobotCommand_message* temp = rc_;
+ rc_ = NULL;
+ return temp;
+}
+void Robot_message::set_allocated_rc(::RobotCommand_message* rc) {
+ delete rc_;
+ rc_ = rc;
+ if (rc) {
+ set_has_rc();
+ } else {
+ clear_has_rc();
+ }
+ // @@protoc_insertion_point(field_set_allocated:Robot_message.rc)
}
+#endif // PROTOBUF_INLINE_NOT_IN_HEADERS
// @@protoc_insertion_point(namespace_scope)
diff --git a/src/proto/Robot_message.pb.h b/src/proto/Robot_message.pb.h
index 66ae584..3d64bee 100644
--- a/src/proto/Robot_message.pb.h
+++ b/src/proto/Robot_message.pb.h
@@ -8,33 +8,42 @@
#include
-#if GOOGLE_PROTOBUF_VERSION < 2005000
+#if GOOGLE_PROTOBUF_VERSION < 3001000
#error This file was generated by a newer version of protoc which is
#error incompatible with your Protocol Buffer headers. Please update
#error your headers.
#endif
-#if 2005000 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION
+#if 3001000 < GOOGLE_PROTOBUF_MIN_PROTOC_VERSION
#error This file was generated by an older version of protoc which is
#error incompatible with your Protocol Buffer headers. Please
#error regenerate this file with a newer version of protoc.
#endif
+#include
+#include
#include
+#include
#include
-#include
-#include
+#include // IWYU pragma: export
+#include // IWYU pragma: export
#include
#include
#include "position_message.pb.h"
#include "RobotCommand_message.pb.h"
// @@protoc_insertion_point(includes)
+class RobotCommand_message;
+class RobotCommand_messageDefaultTypeInternal;
+extern RobotCommand_messageDefaultTypeInternal _RobotCommand_message_default_instance_;
+class Robot_message;
+class Robot_messageDefaultTypeInternal;
+extern Robot_messageDefaultTypeInternal _Robot_message_default_instance_;
+class position_message;
+class position_messageDefaultTypeInternal;
+extern position_messageDefaultTypeInternal _position_message_default_instance_;
// Internal implementation detail -- do not call these.
-void protobuf_AddDesc_Robot_5fmessage_2eproto();
-void protobuf_AssignDesc_Robot_5fmessage_2eproto();
-void protobuf_ShutdownFile_Robot_5fmessage_2eproto();
-
-class Robot_message;
+void protobuf_AddDesc_Robot_5fmessage_2eproto();
+void protobuf_InitDefaults_Robot_5fmessage_2eproto();
enum Robot_message_AgentStatus {
Robot_message_AgentStatus_Idle = 1,
@@ -116,7 +125,7 @@ inline bool Robot_message_AgentRole_Parse(
}
// ===================================================================
-class Robot_message : public ::google::protobuf::Message {
+class Robot_message : public ::google::protobuf::Message /* @@protoc_insertion_point(class_definition:Robot_message) */ {
public:
Robot_message();
virtual ~Robot_message();
@@ -129,54 +138,82 @@ class Robot_message : public ::google::protobuf::Message {
}
inline const ::google::protobuf::UnknownFieldSet& unknown_fields() const {
- return _unknown_fields_;
+ return _internal_metadata_.unknown_fields();
}
inline ::google::protobuf::UnknownFieldSet* mutable_unknown_fields() {
- return &_unknown_fields_;
+ return _internal_metadata_.mutable_unknown_fields();
}
static const ::google::protobuf::Descriptor* descriptor();
static const Robot_message& default_instance();
+ static inline const Robot_message* internal_default_instance() {
+ return reinterpret_cast(
+ &_Robot_message_default_instance_);
+ }
+
void Swap(Robot_message* other);
// implements Message ----------------------------------------------
- Robot_message* New() const;
- void CopyFrom(const ::google::protobuf::Message& from);
- void MergeFrom(const ::google::protobuf::Message& from);
+ inline Robot_message* New() const PROTOBUF_FINAL { return New(NULL); }
+
+ Robot_message* New(::google::protobuf::Arena* arena) const PROTOBUF_FINAL;
+ void CopyFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL;
+ void MergeFrom(const ::google::protobuf::Message& from) PROTOBUF_FINAL;
void CopyFrom(const Robot_message& from);
void MergeFrom(const Robot_message& from);
- void Clear();
- bool IsInitialized() const;
+ void Clear() PROTOBUF_FINAL;
+ bool IsInitialized() const PROTOBUF_FINAL;
- int ByteSize() const;
+ size_t ByteSizeLong() const PROTOBUF_FINAL;
bool MergePartialFromCodedStream(
- ::google::protobuf::io::CodedInputStream* input);
+ ::google::protobuf::io::CodedInputStream* input) PROTOBUF_FINAL;
void SerializeWithCachedSizes(
- ::google::protobuf::io::CodedOutputStream* output) const;
- ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output) const;
- int GetCachedSize() const { return _cached_size_; }
+ ::google::protobuf::io::CodedOutputStream* output) const PROTOBUF_FINAL;
+ ::google::protobuf::uint8* InternalSerializeWithCachedSizesToArray(
+ bool deterministic, ::google::protobuf::uint8* target) const PROTOBUF_FINAL;
+ ::google::protobuf::uint8* SerializeWithCachedSizesToArray(::google::protobuf::uint8* output)
+ const PROTOBUF_FINAL {
+ return InternalSerializeWithCachedSizesToArray(false, output);
+ }
+ int GetCachedSize() const PROTOBUF_FINAL { return _cached_size_; }
private:
void SharedCtor();
void SharedDtor();
- void SetCachedSize(int size) const;
+ void SetCachedSize(int size) const PROTOBUF_FINAL;
+ void InternalSwap(Robot_message* other);
+ private:
+ inline ::google::protobuf::Arena* GetArenaNoVirtual() const {
+ return NULL;
+ }
+ inline void* MaybeArenaPtr() const {
+ return NULL;
+ }
public:
- ::google::protobuf::Metadata GetMetadata() const;
+ ::google::protobuf::Metadata GetMetadata() const PROTOBUF_FINAL;
// nested types ----------------------------------------------------
typedef Robot_message_AgentStatus AgentStatus;
- static const AgentStatus Idle = Robot_message_AgentStatus_Idle;
- static const AgentStatus Passing = Robot_message_AgentStatus_Passing;
- static const AgentStatus Kicking = Robot_message_AgentStatus_Kicking;
- static const AgentStatus Chiping = Robot_message_AgentStatus_Chiping;
- static const AgentStatus FollowingBall = Robot_message_AgentStatus_FollowingBall;
- static const AgentStatus BlockingBall = Robot_message_AgentStatus_BlockingBall;
- static const AgentStatus BlockingRobot = Robot_message_AgentStatus_BlockingRobot;
- static const AgentStatus RecievingPass = Robot_message_AgentStatus_RecievingPass;
+ static const AgentStatus Idle =
+ Robot_message_AgentStatus_Idle;
+ static const AgentStatus Passing =
+ Robot_message_AgentStatus_Passing;
+ static const AgentStatus Kicking =
+ Robot_message_AgentStatus_Kicking;
+ static const AgentStatus Chiping =
+ Robot_message_AgentStatus_Chiping;
+ static const AgentStatus FollowingBall =
+ Robot_message_AgentStatus_FollowingBall;
+ static const AgentStatus BlockingBall =
+ Robot_message_AgentStatus_BlockingBall;
+ static const AgentStatus BlockingRobot =
+ Robot_message_AgentStatus_BlockingRobot;
+ static const AgentStatus RecievingPass =
+ Robot_message_AgentStatus_RecievingPass;
static inline bool AgentStatus_IsValid(int value) {
return Robot_message_AgentStatus_IsValid(value);
}
@@ -199,10 +236,14 @@ class Robot_message : public ::google::protobuf::Message {
}
typedef Robot_message_AgentRegion AgentRegion;
- static const AgentRegion NoRegion = Robot_message_AgentRegion_NoRegion;
- static const AgentRegion Left = Robot_message_AgentRegion_Left;
- static const AgentRegion Center = Robot_message_AgentRegion_Center;
- static const AgentRegion Right = Robot_message_AgentRegion_Right;
+ static const AgentRegion NoRegion =
+ Robot_message_AgentRegion_NoRegion;
+ static const AgentRegion Left =
+ Robot_message_AgentRegion_Left;
+ static const AgentRegion Center =
+ Robot_message_AgentRegion_Center;
+ static const AgentRegion Right =
+ Robot_message_AgentRegion_Right;
static inline bool AgentRegion_IsValid(int value) {
return Robot_message_AgentRegion_IsValid(value);
}
@@ -225,21 +266,36 @@ class Robot_message : public ::google::protobuf::Message {
}
typedef Robot_message_AgentRole AgentRole;
- static const AgentRole NoRole = Robot_message_AgentRole_NoRole;
- static const AgentRole ArcMid = Robot_message_AgentRole_ArcMid;
- static const AgentRole ArcLeft = Robot_message_AgentRole_ArcLeft;
- static const AgentRole ArcRight = Robot_message_AgentRole_ArcRight;
- static const AgentRole FixedPositionLeft = Robot_message_AgentRole_FixedPositionLeft;
- static const AgentRole FixedPositionRight = Robot_message_AgentRole_FixedPositionRight;
- static const AgentRole FixedPositionMid = Robot_message_AgentRole_FixedPositionMid;
- static const AgentRole AttackerLeft = Robot_message_AgentRole_AttackerLeft;
- static const AgentRole AttackerRight = Robot_message_AgentRole_AttackerRight;
- static const AgentRole AttackerMid = Robot_message_AgentRole_AttackerMid;
- static const AgentRole Blocker = Robot_message_AgentRole_Blocker;
- static const AgentRole DefenderLeft = Robot_message_AgentRole_DefenderLeft;
- static const AgentRole DefenderRight = Robot_message_AgentRole_DefenderRight;
- static const AgentRole DefenderMid = Robot_message_AgentRole_DefenderMid;
- static const AgentRole Golie = Robot_message_AgentRole_Golie;
+ static const AgentRole NoRole =
+ Robot_message_AgentRole_NoRole;
+ static const AgentRole ArcMid =
+ Robot_message_AgentRole_ArcMid;
+ static const AgentRole ArcLeft =
+ Robot_message_AgentRole_ArcLeft;
+ static const AgentRole ArcRight =
+ Robot_message_AgentRole_ArcRight;
+ static const AgentRole FixedPositionLeft =
+ Robot_message_AgentRole_FixedPositionLeft;
+ static const AgentRole FixedPositionRight =
+ Robot_message_AgentRole_FixedPositionRight;
+ static const AgentRole FixedPositionMid =
+ Robot_message_AgentRole_FixedPositionMid;
+ static const AgentRole AttackerLeft =
+ Robot_message_AgentRole_AttackerLeft;
+ static const AgentRole AttackerRight =
+ Robot_message_AgentRole_AttackerRight;
+ static const AgentRole AttackerMid =
+ Robot_message_AgentRole_AttackerMid;
+ static const AgentRole Blocker =
+ Robot_message_AgentRole_Blocker;
+ static const AgentRole DefenderLeft =
+ Robot_message_AgentRole_DefenderLeft;
+ static const AgentRole DefenderRight =
+ Robot_message_AgentRole_DefenderRight;
+ static const AgentRole DefenderMid =
+ Robot_message_AgentRole_DefenderMid;
+ static const AgentRole Golie =
+ Robot_message_AgentRole_Golie;
static inline bool AgentRole_IsValid(int value) {
return Robot_message_AgentRole_IsValid(value);
}
@@ -264,149 +320,157 @@ class Robot_message : public ::google::protobuf::Message {
// accessors -------------------------------------------------------
// required bool isValid = 1;
- inline bool has_isvalid() const;
- inline void clear_isvalid();
+ bool has_isvalid() const;
+ void clear_isvalid();
static const int kIsValidFieldNumber = 1;
- inline bool isvalid() const;
- inline void set_isvalid(bool value);
+ bool isvalid() const;
+ void set_isvalid(bool value);
// required .position_message position = 2;
- inline bool has_position() const;
- inline void clear_position();
+ bool has_position() const;
+ void clear_position();
static const int kPositionFieldNumber = 2;
- inline const ::position_message& position() const;
- inline ::position_message* mutable_position();
- inline ::position_message* release_position();
- inline void set_allocated_position(::position_message* position);
+ const ::position_message& position() const;
+ ::position_message* mutable_position();
+ ::position_message* release_position();
+ void set_allocated_position(::position_message* position);
// required .position_message velocity = 3;
- inline bool has_velocity() const;
- inline void clear_velocity();
+ bool has_velocity() const;
+ void clear_velocity();
static const int kVelocityFieldNumber = 3;
- inline const ::position_message& velocity() const;
- inline ::position_message* mutable_velocity();
- inline ::position_message* release_velocity();
- inline void set_allocated_velocity(::position_message* velocity);
+ const ::position_message& velocity() const;
+ ::position_message* mutable_velocity();
+ ::position_message* release_velocity();
+ void set_allocated_velocity(::position_message* velocity);
// optional .Robot_message.AgentStatus status = 4;
- inline bool has_status() const;
- inline void clear_status();
+ bool has_status() const;
+ void clear_status();
static const int kStatusFieldNumber = 4;
- inline ::Robot_message_AgentStatus status() const;
- inline void set_status(::Robot_message_AgentStatus value);
+ ::Robot_message_AgentStatus status() const;
+ void set_status(::Robot_message_AgentStatus value);
// optional .Robot_message.AgentRole role = 5;
- inline bool has_role() const;
- inline void clear_role();
+ bool has_role() const;
+ void clear_role();
static const int kRoleFieldNumber = 5;
- inline ::Robot_message_AgentRole role() const;
- inline void set_role(::Robot_message_AgentRole value);
+ ::Robot_message_AgentRole role() const;
+ void set_role(::Robot_message_AgentRole value);
// optional .Robot_message.AgentRegion region = 6;
- inline bool has_region() const;
- inline void clear_region();
+ bool has_region() const;
+ void clear_region();
static const int kRegionFieldNumber = 6;
- inline ::Robot_message_AgentRegion region() const;
- inline void set_region(::Robot_message_AgentRegion value);
+ ::Robot_message_AgentRegion region() const;
+ void set_region(::Robot_message_AgentRegion value);
// optional .RobotCommand_message rc = 7;
- inline bool has_rc() const;
- inline void clear_rc();
+ bool has_rc() const;
+ void clear_rc();
static const int kRcFieldNumber = 7;
- inline const ::RobotCommand_message& rc() const;
- inline ::RobotCommand_message* mutable_rc();
- inline ::RobotCommand_message* release_rc();
- inline void set_allocated_rc(::RobotCommand_message* rc);
+ const ::RobotCommand_message& rc() const;
+ ::RobotCommand_message* mutable_rc();
+ ::RobotCommand_message* release_rc();
+ void set_allocated_rc(::RobotCommand_message* rc);
// @@protoc_insertion_point(class_scope:Robot_message)
private:
- inline void set_has_isvalid();
- inline void clear_has_isvalid();
- inline void set_has_position();
- inline void clear_has_position();
- inline void set_has_velocity();
- inline void clear_has_velocity();
- inline void set_has_status();
- inline void clear_has_status();
- inline void set_has_role();
- inline void clear_has_role();
- inline void set_has_region();
- inline void clear_has_region();
- inline void set_has_rc();
- inline void clear_has_rc();
-
- ::google::protobuf::UnknownFieldSet _unknown_fields_;
-
+ void set_has_isvalid();
+ void clear_has_isvalid();
+ void set_has_position();
+ void clear_has_position();
+ void set_has_velocity();
+ void clear_has_velocity();
+ void set_has_status();
+ void clear_has_status();
+ void set_has_role();
+ void clear_has_role();
+ void set_has_region();
+ void clear_has_region();
+ void set_has_rc();
+ void clear_has_rc();
+
+ // helper for ByteSizeLong()
+ size_t RequiredFieldsByteSizeFallback() const;
+
+ ::google::protobuf::internal::InternalMetadataWithArena _internal_metadata_;
+ ::google::protobuf::internal::HasBits<1> _has_bits_;
+ mutable int _cached_size_;
::position_message* position_;
+ ::position_message* velocity_;
+ ::RobotCommand_message* rc_;
bool isvalid_;
+ int region_;
int status_;
- ::position_message* velocity_;
int role_;
- int region_;
- ::RobotCommand_message* rc_;
-
- mutable int _cached_size_;
- ::google::protobuf::uint32 _has_bits_[(7 + 31) / 32];
-
- friend void protobuf_AddDesc_Robot_5fmessage_2eproto();
- friend void protobuf_AssignDesc_Robot_5fmessage_2eproto();
+ friend void protobuf_InitDefaults_Robot_5fmessage_2eproto_impl();
+ friend void protobuf_AddDesc_Robot_5fmessage_2eproto_impl();
+ friend const ::google::protobuf::uint32* protobuf_Offsets_Robot_5fmessage_2eproto();
friend void protobuf_ShutdownFile_Robot_5fmessage_2eproto();
- void InitAsDefaultInstance();
- static Robot_message* default_instance_;
};
// ===================================================================
// ===================================================================
+#if !PROTOBUF_INLINE_NOT_IN_HEADERS
// Robot_message
// required bool isValid = 1;
inline bool Robot_message::has_isvalid() const {
- return (_has_bits_[0] & 0x00000001u) != 0;
+ return (_has_bits_[0] & 0x00000008u) != 0;
}
inline void Robot_message::set_has_isvalid() {
- _has_bits_[0] |= 0x00000001u;
+ _has_bits_[0] |= 0x00000008u;
}
inline void Robot_message::clear_has_isvalid() {
- _has_bits_[0] &= ~0x00000001u;
+ _has_bits_[0] &= ~0x00000008u;
}
inline void Robot_message::clear_isvalid() {
isvalid_ = false;
clear_has_isvalid();
}
inline bool Robot_message::isvalid() const {
+ // @@protoc_insertion_point(field_get:Robot_message.isValid)
return isvalid_;
}
inline void Robot_message::set_isvalid(bool value) {
set_has_isvalid();
isvalid_ = value;
+ // @@protoc_insertion_point(field_set:Robot_message.isValid)
}
// required .position_message position = 2;
inline bool Robot_message::has_position() const {
- return (_has_bits_[0] & 0x00000002u) != 0;
+ return (_has_bits_[0] & 0x00000001u) != 0;
}
inline void Robot_message::set_has_position() {
- _has_bits_[0] |= 0x00000002u;
+ _has_bits_[0] |= 0x00000001u;
}
inline void Robot_message::clear_has_position() {
- _has_bits_[0] &= ~0x00000002u;
+ _has_bits_[0] &= ~0x00000001u;
}
inline void Robot_message::clear_position() {
if (position_ != NULL) position_->::position_message::Clear();
clear_has_position();
}
inline const ::position_message& Robot_message::position() const {
- return position_ != NULL ? *position_ : *default_instance_->position_;
+ // @@protoc_insertion_point(field_get:Robot_message.position)
+ return position_ != NULL ? *position_
+ : *::position_message::internal_default_instance();
}
inline ::position_message* Robot_message::mutable_position() {
set_has_position();
- if (position_ == NULL) position_ = new ::position_message;
+ if (position_ == NULL) {
+ position_ = new ::position_message;
+ }
+ // @@protoc_insertion_point(field_mutable:Robot_message.position)
return position_;
}
inline ::position_message* Robot_message::release_position() {
+ // @@protoc_insertion_point(field_release:Robot_message.position)
clear_has_position();
::position_message* temp = position_;
position_ = NULL;
@@ -420,31 +484,38 @@ inline void Robot_message::set_allocated_position(::position_message* position)
} else {
clear_has_position();
}
+ // @@protoc_insertion_point(field_set_allocated:Robot_message.position)
}
// required .position_message velocity = 3;
inline bool Robot_message::has_velocity() const {
- return (_has_bits_[0] & 0x00000004u) != 0;
+ return (_has_bits_[0] & 0x00000002u) != 0;
}
inline void Robot_message::set_has_velocity() {
- _has_bits_[0] |= 0x00000004u;
+ _has_bits_[0] |= 0x00000002u;
}
inline void Robot_message::clear_has_velocity() {
- _has_bits_[0] &= ~0x00000004u;
+ _has_bits_[0] &= ~0x00000002u;
}
inline void Robot_message::clear_velocity() {
if (velocity_ != NULL) velocity_->::position_message::Clear();
clear_has_velocity();
}
inline const ::position_message& Robot_message::velocity() const {
- return velocity_ != NULL ? *velocity_ : *default_instance_->velocity_;
+ // @@protoc_insertion_point(field_get:Robot_message.velocity)
+ return velocity_ != NULL ? *velocity_
+ : *::position_message::internal_default_instance();
}
inline ::position_message* Robot_message::mutable_velocity() {
set_has_velocity();
- if (velocity_ == NULL) velocity_ = new ::position_message;
+ if (velocity_ == NULL) {
+ velocity_ = new ::position_message;
+ }
+ // @@protoc_insertion_point(field_mutable:Robot_message.velocity)
return velocity_;
}
inline ::position_message* Robot_message::release_velocity() {
+ // @@protoc_insertion_point(field_release:Robot_message.velocity)
clear_has_velocity();
::position_message* temp = velocity_;
velocity_ = NULL;
@@ -458,100 +529,113 @@ inline void Robot_message::set_allocated_velocity(::position_message* velocity)
} else {
clear_has_velocity();
}
+ // @@protoc_insertion_point(field_set_allocated:Robot_message.velocity)
}
// optional .Robot_message.AgentStatus status = 4;
inline bool Robot_message::has_status() const {
- return (_has_bits_[0] & 0x00000008u) != 0;
+ return (_has_bits_[0] & 0x00000020u) != 0;
}
inline void Robot_message::set_has_status() {
- _has_bits_[0] |= 0x00000008u;
+ _has_bits_[0] |= 0x00000020u;
}
inline void Robot_message::clear_has_status() {
- _has_bits_[0] &= ~0x00000008u;
+ _has_bits_[0] &= ~0x00000020u;
}
inline void Robot_message::clear_status() {
status_ = 1;
clear_has_status();
}
inline ::Robot_message_AgentStatus Robot_message::status() const {
+ // @@protoc_insertion_point(field_get:Robot_message.status)
return static_cast< ::Robot_message_AgentStatus >(status_);
}
inline void Robot_message::set_status(::Robot_message_AgentStatus value) {
assert(::Robot_message_AgentStatus_IsValid(value));
set_has_status();
status_ = value;
+ // @@protoc_insertion_point(field_set:Robot_message.status)
}
// optional .Robot_message.AgentRole role = 5;
inline bool Robot_message::has_role() const {
- return (_has_bits_[0] & 0x00000010u) != 0;
+ return (_has_bits_[0] & 0x00000040u) != 0;
}
inline void Robot_message::set_has_role() {
- _has_bits_[0] |= 0x00000010u;
+ _has_bits_[0] |= 0x00000040u;
}
inline void Robot_message::clear_has_role() {
- _has_bits_[0] &= ~0x00000010u;
+ _has_bits_[0] &= ~0x00000040u;
}
inline void Robot_message::clear_role() {
role_ = 31;
clear_has_role();
}
inline ::Robot_message_AgentRole Robot_message::role() const {
+ // @@protoc_insertion_point(field_get:Robot_message.role)
return static_cast< ::Robot_message_AgentRole >(role_);
}
inline void Robot_message::set_role(::Robot_message_AgentRole value) {
assert(::Robot_message_AgentRole_IsValid(value));
set_has_role();
role_ = value;
+ // @@protoc_insertion_point(field_set:Robot_message.role)
}
// optional .Robot_message.AgentRegion region = 6;
inline bool Robot_message::has_region() const {
- return (_has_bits_[0] & 0x00000020u) != 0;
+ return (_has_bits_[0] & 0x00000010u) != 0;
}
inline void Robot_message::set_has_region() {
- _has_bits_[0] |= 0x00000020u;
+ _has_bits_[0] |= 0x00000010u;
}
inline void Robot_message::clear_has_region() {
- _has_bits_[0] &= ~0x00000020u;
+ _has_bits_[0] &= ~0x00000010u;
}
inline void Robot_message::clear_region() {
region_ = 21;
clear_has_region();
}
inline ::Robot_message_AgentRegion Robot_message::region() const {
+ // @@protoc_insertion_point(field_get:Robot_message.region)
return static_cast< ::Robot_message_AgentRegion >(region_);
}
inline void Robot_message::set_region(::Robot_message_AgentRegion value) {
assert(::Robot_message_AgentRegion_IsValid(value));
set_has_region();
region_ = value;
+ // @@protoc_insertion_point(field_set:Robot_message.region)
}
// optional .RobotCommand_message rc = 7;
inline bool Robot_message::has_rc() const {
- return (_has_bits_[0] & 0x00000040u) != 0;
+ return (_has_bits_[0] & 0x00000004u) != 0;
}
inline void Robot_message::set_has_rc() {
- _has_bits_[0] |= 0x00000040u;
+ _has_bits_[0] |= 0x00000004u;
}
inline void Robot_message::clear_has_rc() {
- _has_bits_[0] &= ~0x00000040u;
+ _has_bits_[0] &= ~0x00000004u;
}
inline void Robot_message::clear_rc() {
if (rc_ != NULL) rc_->::RobotCommand_message::Clear();
clear_has_rc();
}
inline const ::RobotCommand_message& Robot_message::rc() const {
- return rc_ != NULL ? *rc_ : *default_instance_->rc_;
+ // @@protoc_insertion_point(field_get:Robot_message.rc)
+ return rc_ != NULL ? *rc_
+ : *::RobotCommand_message::internal_default_instance();
}
inline ::RobotCommand_message* Robot_message::mutable_rc() {
set_has_rc();
- if (rc_ == NULL) rc_ = new ::RobotCommand_message;
+ if (rc_ == NULL) {
+ rc_ = new ::RobotCommand_message;
+ }
+ // @@protoc_insertion_point(field_mutable:Robot_message.rc)
return rc_;
}
inline ::RobotCommand_message* Robot_message::release_rc() {
+ // @@protoc_insertion_point(field_release:Robot_message.rc)
clear_has_rc();
::RobotCommand_message* temp = rc_;
rc_ = NULL;
@@ -565,30 +649,36 @@ inline void Robot_message::set_allocated_rc(::RobotCommand_message* rc) {
} else {
clear_has_rc();
}
+ // @@protoc_insertion_point(field_set_allocated:Robot_message.rc)
}
+#endif // !PROTOBUF_INLINE_NOT_IN_HEADERS
// @@protoc_insertion_point(namespace_scope)
+
#ifndef SWIG
namespace google {
namespace protobuf {
+template <> struct is_proto_enum< ::Robot_message_AgentStatus> : ::google::protobuf::internal::true_type {};
template <>
inline const EnumDescriptor* GetEnumDescriptor< ::Robot_message_AgentStatus>() {
return ::Robot_message_AgentStatus_descriptor();
}
+template <> struct is_proto_enum< ::Robot_message_AgentRegion> : ::google::protobuf::internal::true_type {};
template <>
inline const EnumDescriptor* GetEnumDescriptor< ::Robot_message_AgentRegion>() {
return ::Robot_message_AgentRegion_descriptor();
}
+template <> struct is_proto_enum< ::Robot_message_AgentRole> : ::google::protobuf::internal::true_type {};
template <>
inline const EnumDescriptor* GetEnumDescriptor< ::Robot_message_AgentRole>() {
return ::Robot_message_AgentRole_descriptor();
}
-} // namespace google
} // namespace protobuf
+} // namespace google
#endif // SWIG
// @@protoc_insertion_point(global_scope)
diff --git a/src/proto/grSim_Commands.pb.cc b/src/proto/grSim_Commands.pb.cc
index e8e69b1..8bfc07d 100644
--- a/src/proto/grSim_Commands.pb.cc
+++ b/src/proto/grSim_Commands.pb.cc
@@ -7,6 +7,7 @@
#include
#include
+#include
#include
#include
#include
@@ -15,27 +16,25 @@
#include
#include
// @@protoc_insertion_point(includes)
+class grSim_Robot_CommandDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed {};
+grSim_Robot_CommandDefaultTypeInternal _grSim_Robot_Command_default_instance_;
+class grSim_CommandsDefaultTypeInternal : public ::google::protobuf::internal::ExplicitlyConstructed {};
+grSim_CommandsDefaultTypeInternal _grSim_Commands_default_instance_;
namespace {
-const ::google::protobuf::Descriptor* grSim_Robot_Command_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- grSim_Robot_Command_reflection_ = NULL;
-const ::google::protobuf::Descriptor* grSim_Commands_descriptor_ = NULL;
-const ::google::protobuf::internal::GeneratedMessageReflection*
- grSim_Commands_reflection_ = NULL;
+::google::protobuf::Metadata file_level_metadata[2];
} // namespace
-void protobuf_AssignDesc_grSim_5fCommands_2eproto() {
- protobuf_AddDesc_grSim_5fCommands_2eproto();
- const ::google::protobuf::FileDescriptor* file =
- ::google::protobuf::DescriptorPool::generated_pool()->FindFileByName(
- "grSim_Commands.proto");
- GOOGLE_CHECK(file != NULL);
- grSim_Robot_Command_descriptor_ = file->message_type(0);
- static const int grSim_Robot_Command_offsets_[12] = {
+const ::google::protobuf::uint32* protobuf_Offsets_grSim_5fCommands_2eproto() GOOGLE_ATTRIBUTE_COLD;
+const ::google::protobuf::uint32* protobuf_Offsets_grSim_5fCommands_2eproto() {
+ static const ::google::protobuf::uint32 offsets[] = {
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Robot_Command, _has_bits_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Robot_Command, _internal_metadata_),
+ ~0u, // no _extensions_
+ ~0u, // no _oneof_case_
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Robot_Command, id_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Robot_Command, kickspeedx_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Robot_Command, kickspeedz_),
@@ -48,88 +47,110 @@ void protobuf_AssignDesc_grSim_5fCommands_2eproto() {
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Robot_Command, wheel2_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Robot_Command, wheel3_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Robot_Command, wheel4_),
- };
- grSim_Robot_Command_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- grSim_Robot_Command_descriptor_,
- grSim_Robot_Command::default_instance_,
- grSim_Robot_Command_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Robot_Command, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Robot_Command, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(grSim_Robot_Command));
- grSim_Commands_descriptor_ = file->message_type(1);
- static const int grSim_Commands_offsets_[3] = {
+ 0,
+ 1,
+ 2,
+ 3,
+ 4,
+ 5,
+ 6,
+ 7,
+ 8,
+ 9,
+ 10,
+ 11,
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Commands, _has_bits_),
+ GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Commands, _internal_metadata_),
+ ~0u, // no _extensions_
+ ~0u, // no _oneof_case_
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Commands, timestamp_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Commands, isteamyellow_),
GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Commands, robot_commands_),
+ 0,
+ 1,
+ 2,
};
- grSim_Commands_reflection_ =
- new ::google::protobuf::internal::GeneratedMessageReflection(
- grSim_Commands_descriptor_,
- grSim_Commands::default_instance_,
- grSim_Commands_offsets_,
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Commands, _has_bits_[0]),
- GOOGLE_PROTOBUF_GENERATED_MESSAGE_FIELD_OFFSET(grSim_Commands, _unknown_fields_),
- -1,
- ::google::protobuf::DescriptorPool::generated_pool(),
- ::google::protobuf::MessageFactory::generated_factory(),
- sizeof(grSim_Commands));
+ return offsets;
}
+static const ::google::protobuf::internal::MigrationSchema schemas[] = {
+ { 0, 16, sizeof(grSim_Robot_Command)},
+ { 28, 35, sizeof(grSim_Commands)},
+};
+
+static const ::google::protobuf::internal::DefaultInstanceData file_default_instances[] = {
+ {reinterpret_cast(&_grSim_Robot_Command_default_instance_), NULL},
+ {reinterpret_cast(&_grSim_Commands_default_instance_), NULL},
+};
+
namespace {
-GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AssignDescriptors_once_);
-inline void protobuf_AssignDescriptorsOnce() {
- ::google::protobuf::GoogleOnceInit(&protobuf_AssignDescriptors_once_,
- &protobuf_AssignDesc_grSim_5fCommands_2eproto);
+void protobuf_AssignDescriptors() {
+ protobuf_AddDesc_grSim_5fCommands_2eproto();
+ ::google::protobuf::MessageFactory* factory = NULL;
+ AssignDescriptors(
+ "grSim_Commands.proto", schemas, file_default_instances, protobuf_Offsets_grSim_5fCommands_2eproto(), factory,
+ file_level_metadata, NULL, NULL);
}
+void protobuf_AssignDescriptorsOnce() {
+ static GOOGLE_PROTOBUF_DECLARE_ONCE(once);
+ ::google::protobuf::GoogleOnceInit(&once, &protobuf_AssignDescriptors);
+}
+
+void protobuf_RegisterTypes(const ::std::string&) GOOGLE_ATTRIBUTE_COLD;
void protobuf_RegisterTypes(const ::std::string&) {
protobuf_AssignDescriptorsOnce();
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- grSim_Robot_Command_descriptor_, &grSim_Robot_Command::default_instance());
- ::google::protobuf::MessageFactory::InternalRegisterGeneratedMessage(
- grSim_Commands_descriptor_, &grSim_Commands::default_instance());
+ ::google::protobuf::internal::RegisterAllTypes(file_level_metadata, 2);
}
} // namespace
void protobuf_ShutdownFile_grSim_5fCommands_2eproto() {
- delete grSim_Robot_Command::default_instance_;
- delete grSim_Robot_Command_reflection_;
- delete grSim_Commands::default_instance_;
- delete grSim_Commands_reflection_;
+ _grSim_Robot_Command_default_instance_.Shutdown();
+ delete file_level_metadata[0].reflection;
+ _grSim_Commands_default_instance_.Shutdown();
+ delete file_level_metadata[1].reflection;
}
-void protobuf_AddDesc_grSim_5fCommands_2eproto() {
- static bool already_here = false;
- if (already_here) return;
- already_here = true;
+void protobuf_InitDefaults_grSim_5fCommands_2eproto_impl() {
GOOGLE_PROTOBUF_VERIFY_VERSION;
+ ::google::protobuf::internal::InitProtobufDefaults();
+ _grSim_Robot_Command_default_instance_.DefaultConstruct();
+ _grSim_Commands_default_instance_.DefaultConstruct();
+}
+
+void protobuf_InitDefaults_grSim_5fCommands_2eproto() {
+ static GOOGLE_PROTOBUF_DECLARE_ONCE(once);
+ ::google::protobuf::GoogleOnceInit(&once, &protobuf_InitDefaults_grSim_5fCommands_2eproto_impl);
+}
+void protobuf_AddDesc_grSim_5fCommands_2eproto_impl() {
+ protobuf_InitDefaults_grSim_5fCommands_2eproto();
+ static const char descriptor[] = {
+ "\n\024grSim_Commands.proto\"\352\001\n\023grSim_Robot_C"
+ "ommand\022\n\n\002id\030\001 \002(\r\022\022\n\nkickspeedx\030\002 \002(\002\022\022"
+ "\n\nkickspeedz\030\003 \002(\002\022\022\n\nveltangent\030\004 \002(\002\022\021"
+ "\n\tvelnormal\030\005 \002(\002\022\022\n\nvelangular\030\006 \002(\002\022\017\n"
+ "\007spinner\030\007 \002(\010\022\023\n\013wheelsspeed\030\010 \002(\010\022\016\n\006w"
+ "heel1\030\t \001(\002\022\016\n\006wheel2\030\n \001(\002\022\016\n\006wheel3\030\013 "
+ "\001(\002\022\016\n\006wheel4\030\014 \001(\002\"g\n\016grSim_Commands\022\021\n"
+ "\ttimestamp\030\001 \002(\001\022\024\n\014isteamyellow\030\002 \002(\010\022,"
+ "\n\016robot_commands\030\003 \003(\0132\024.grSim_Robot_Com"
+ "mand"
+ };
::google::protobuf::DescriptorPool::InternalAddGeneratedFile(
- "\n\024grSim_Commands.proto\"\352\001\n\023grSim_Robot_C"
- "ommand\022\n\n\002id\030\001 \002(\r\022\022\n\nkickspeedx\030\002 \002(\002\022\022"
- "\n\nkickspeedz\030\003 \002(\002\022\022\n\nveltangent\030\004 \002(\002\022\021"
- "\n\tvelnormal\030\005 \002(\002\022\022\n\nvelangular\030\006 \002(\002\022\017\n"
- "\007spinner\030\007 \002(\010\022\023\n\013wheelsspeed\030\010 \002(\010\022\016\n\006w"
- "heel1\030\t \001(\002\022\016\n\006wheel2\030\n \001(\002\022\016\n\006wheel3\030\013 "
- "\001(\002\022\016\n\006wheel4\030\014 \001(\002\"g\n\016grSim_Commands\022\021\n"
- "\ttimestamp\030\001 \002(\001\022\024\n\014isteamyellow\030\002 \002(\010\022,"
- "\n\016robot_commands\030\003 \003(\0132\024.grSim_Robot_Com"
- "mand", 364);
+ descriptor, 364);
::google::protobuf::MessageFactory::InternalRegisterGeneratedFile(
"grSim_Commands.proto", &protobuf_RegisterTypes);
- grSim_Robot_Command::default_instance_ = new grSim_Robot_Command();
- grSim_Commands::default_instance_ = new grSim_Commands();
- grSim_Robot_Command::default_instance_->InitAsDefaultInstance();
- grSim_Commands::default_instance_->InitAsDefaultInstance();
::google::protobuf::internal::OnShutdown(&protobuf_ShutdownFile_grSim_5fCommands_2eproto);
}
+GOOGLE_PROTOBUF_DECLARE_ONCE(protobuf_AddDesc_grSim_5fCommands_2eproto_once_);
+void protobuf_AddDesc_grSim_5fCommands_2eproto() {
+ ::google::protobuf::GoogleOnceInit(&protobuf_AddDesc_grSim_5fCommands_2eproto_once_,
+ &protobuf_AddDesc_grSim_5fCommands_2eproto_impl);
+}
// Force AddDescriptors() to be called at static initialization time.
struct StaticDescriptorInitializer_grSim_5fCommands_2eproto {
StaticDescriptorInitializer_grSim_5fCommands_2eproto() {
@@ -139,7 +160,7 @@ struct StaticDescriptorInitializer_grSim_5fCommands_2eproto {
// ===================================================================
-#ifndef _MSC_VER
+#if !defined(_MSC_VER) || _MSC_VER >= 1900
const int grSim_Robot_Command::kIdFieldNumber;
const int grSim_Robot_Command::kKickspeedxFieldNumber;
const int grSim_Robot_Command::kKickspeedzFieldNumber;
@@ -152,46 +173,40 @@ const int grSim_Robot_Command::kWheel1FieldNumber;
const int grSim_Robot_Command::kWheel2FieldNumber;
const int grSim_Robot_Command::kWheel3FieldNumber;
const int grSim_Robot_Command::kWheel4FieldNumber;
-#endif // !_MSC_VER
+#endif // !defined(_MSC_VER) || _MSC_VER >= 1900
grSim_Robot_Command::grSim_Robot_Command()
- : ::google::protobuf::Message() {
+ : ::google::protobuf::Message(), _internal_metadata_(NULL) {
+ if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) {
+ protobuf_InitDefaults_grSim_5fCommands_2eproto();
+ }
SharedCtor();
+ // @@protoc_insertion_point(constructor:grSim_Robot_Command)
}
-
-void grSim_Robot_Command::InitAsDefaultInstance() {
-}
-
grSim_Robot_Command::grSim_Robot_Command(const grSim_Robot_Command& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
+ : ::google::protobuf::Message(),
+ _internal_metadata_(NULL),
+ _has_bits_(from._has_bits_),
+ _cached_size_(0) {
+ _internal_metadata_.MergeFrom(from._internal_metadata_);
+ ::memcpy(&id_, &from.id_,
+ reinterpret_cast(&wheel4_) -
+ reinterpret_cast(&id_) + sizeof(wheel4_));
+ // @@protoc_insertion_point(copy_constructor:grSim_Robot_Command)
}
void grSim_Robot_Command::SharedCtor() {
_cached_size_ = 0;
- id_ = 0u;
- kickspeedx_ = 0;
- kickspeedz_ = 0;
- veltangent_ = 0;
- velnormal_ = 0;
- velangular_ = 0;
- spinner_ = false;
- wheelsspeed_ = false;
- wheel1_ = 0;
- wheel2_ = 0;
- wheel3_ = 0;
- wheel4_ = 0;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ ::memset(&id_, 0, reinterpret_cast(&wheel4_) -
+ reinterpret_cast(&id_) + sizeof(wheel4_));
}
grSim_Robot_Command::~grSim_Robot_Command() {
+ // @@protoc_insertion_point(destructor:grSim_Robot_Command)
SharedDtor();
}
void grSim_Robot_Command::SharedDtor() {
- if (this != default_instance_) {
- }
}
void grSim_Robot_Command::SetCachedSize(int size) const {
@@ -201,243 +216,208 @@ void grSim_Robot_Command::SetCachedSize(int size) const {
}
const ::google::protobuf::Descriptor* grSim_Robot_Command::descriptor() {
protobuf_AssignDescriptorsOnce();
- return grSim_Robot_Command_descriptor_;
+ return file_level_metadata[0].descriptor;
}
const grSim_Robot_Command& grSim_Robot_Command::default_instance() {
- if (default_instance_ == NULL) protobuf_AddDesc_grSim_5fCommands_2eproto();
- return *default_instance_;
+ protobuf_InitDefaults_grSim_5fCommands_2eproto();
+ return *internal_default_instance();
}
-grSim_Robot_Command* grSim_Robot_Command::default_instance_ = NULL;
-
-grSim_Robot_Command* grSim_Robot_Command::New() const {
- return new grSim_Robot_Command;
+grSim_Robot_Command* grSim_Robot_Command::New(::google::protobuf::Arena* arena) const {
+ grSim_Robot_Command* n = new grSim_Robot_Command;
+ if (arena != NULL) {
+ arena->Own(n);
+ }
+ return n;
}
void grSim_Robot_Command::Clear() {
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
- id_ = 0u;
- kickspeedx_ = 0;
- kickspeedz_ = 0;
- veltangent_ = 0;
- velnormal_ = 0;
- velangular_ = 0;
- spinner_ = false;
- wheelsspeed_ = false;
- }
- if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) {
- wheel1_ = 0;
- wheel2_ = 0;
- wheel3_ = 0;
- wheel4_ = 0;
- }
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
- mutable_unknown_fields()->Clear();
+// @@protoc_insertion_point(message_clear_start:grSim_Robot_Command)
+ if (_has_bits_[0 / 32] & 255u) {
+ ::memset(&id_, 0, reinterpret_cast(&wheelsspeed_) -
+ reinterpret_cast(&id_) + sizeof(wheelsspeed_));
+ }
+ if (_has_bits_[8 / 32] & 3840u) {
+ ::memset(&wheel1_, 0, reinterpret_cast(&wheel4_) -
+ reinterpret_cast(&wheel1_) + sizeof(wheel4_));
+ }
+ _has_bits_.Clear();
+ _internal_metadata_.Clear();
}
bool grSim_Robot_Command::MergePartialFromCodedStream(
::google::protobuf::io::CodedInputStream* input) {
-#define DO_(EXPRESSION) if (!(EXPRESSION)) return false
+#define DO_(EXPRESSION) if (!GOOGLE_PREDICT_TRUE(EXPRESSION)) goto failure
::google::protobuf::uint32 tag;
- while ((tag = input->ReadTag()) != 0) {
+ // @@protoc_insertion_point(parse_start:grSim_Robot_Command)
+ for (;;) {
+ ::std::pair< ::google::protobuf::uint32, bool> p = input->ReadTagWithCutoffNoLastTag(127u);
+ tag = p.first;
+ if (!p.second) goto handle_unusual;
switch (::google::protobuf::internal::WireFormatLite::GetTagFieldNumber(tag)) {
// required uint32 id = 1;
case 1: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
+ if (tag == 8u) {
+ set_has_id();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
::google::protobuf::uint32, ::google::protobuf::internal::WireFormatLite::TYPE_UINT32>(
input, &id_)));
- set_has_id();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(21)) goto parse_kickspeedx;
break;
}
// required float kickspeedx = 2;
case 2: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_kickspeedx:
+ if (tag == 21u) {
+ set_has_kickspeedx();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
input, &kickspeedx_)));
- set_has_kickspeedx();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(29)) goto parse_kickspeedz;
break;
}
// required float kickspeedz = 3;
case 3: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_kickspeedz:
+ if (tag == 29u) {
+ set_has_kickspeedz();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
input, &kickspeedz_)));
- set_has_kickspeedz();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(37)) goto parse_veltangent;
break;
}
// required float veltangent = 4;
case 4: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_veltangent:
+ if (tag == 37u) {
+ set_has_veltangent();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
input, &veltangent_)));
- set_has_veltangent();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(45)) goto parse_velnormal;
break;
}
// required float velnormal = 5;
case 5: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_velnormal:
+ if (tag == 45u) {
+ set_has_velnormal();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
input, &velnormal_)));
- set_has_velnormal();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(53)) goto parse_velangular;
break;
}
// required float velangular = 6;
case 6: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_velangular:
+ if (tag == 53u) {
+ set_has_velangular();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
input, &velangular_)));
- set_has_velangular();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(56)) goto parse_spinner;
break;
}
// required bool spinner = 7;
case 7: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_spinner:
+ if (tag == 56u) {
+ set_has_spinner();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>(
input, &spinner_)));
- set_has_spinner();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(64)) goto parse_wheelsspeed;
break;
}
// required bool wheelsspeed = 8;
case 8: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_VARINT) {
- parse_wheelsspeed:
+ if (tag == 64u) {
+ set_has_wheelsspeed();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
bool, ::google::protobuf::internal::WireFormatLite::TYPE_BOOL>(
input, &wheelsspeed_)));
- set_has_wheelsspeed();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(77)) goto parse_wheel1;
break;
}
// optional float wheel1 = 9;
case 9: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_wheel1:
+ if (tag == 77u) {
+ set_has_wheel1();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
input, &wheel1_)));
- set_has_wheel1();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(85)) goto parse_wheel2;
break;
}
// optional float wheel2 = 10;
case 10: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_wheel2:
+ if (tag == 85u) {
+ set_has_wheel2();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
input, &wheel2_)));
- set_has_wheel2();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(93)) goto parse_wheel3;
break;
}
// optional float wheel3 = 11;
case 11: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_wheel3:
+ if (tag == 93u) {
+ set_has_wheel3();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
input, &wheel3_)));
- set_has_wheel3();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectTag(101)) goto parse_wheel4;
break;
}
// optional float wheel4 = 12;
case 12: {
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
- ::google::protobuf::internal::WireFormatLite::WIRETYPE_FIXED32) {
- parse_wheel4:
+ if (tag == 101u) {
+ set_has_wheel4();
DO_((::google::protobuf::internal::WireFormatLite::ReadPrimitive<
float, ::google::protobuf::internal::WireFormatLite::TYPE_FLOAT>(
input, &wheel4_)));
- set_has_wheel4();
} else {
- goto handle_uninterpreted;
+ goto handle_unusual;
}
- if (input->ExpectAtEnd()) return true;
break;
}
default: {
- handle_uninterpreted:
- if (::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
+ handle_unusual:
+ if (tag == 0 ||
+ ::google::protobuf::internal::WireFormatLite::GetTagWireType(tag) ==
::google::protobuf::internal::WireFormatLite::WIRETYPE_END_GROUP) {
- return true;
+ goto success;
}
DO_(::google::protobuf::internal::WireFormat::SkipField(
input, tag, mutable_unknown_fields()));
@@ -445,12 +425,18 @@ bool grSim_Robot_Command::MergePartialFromCodedStream(
}
}
}
+success:
+ // @@protoc_insertion_point(parse_success:grSim_Robot_Command)
return true;
+failure:
+ // @@protoc_insertion_point(parse_failure:grSim_Robot_Command)
+ return false;
#undef DO_
}
void grSim_Robot_Command::SerializeWithCachedSizes(
::google::protobuf::io::CodedOutputStream* output) const {
+ // @@protoc_insertion_point(serialize_start:grSim_Robot_Command)
// required uint32 id = 1;
if (has_id()) {
::google::protobuf::internal::WireFormatLite::WriteUInt32(1, this->id(), output);
@@ -511,14 +497,17 @@ void grSim_Robot_Command::SerializeWithCachedSizes(
::google::protobuf::internal::WireFormatLite::WriteFloat(12, this->wheel4(), output);
}
- if (!unknown_fields().empty()) {
+ if (_internal_metadata_.have_unknown_fields()) {
::google::protobuf::internal::WireFormat::SerializeUnknownFields(
unknown_fields(), output);
}
+ // @@protoc_insertion_point(serialize_end:grSim_Robot_Command)
}
-::google::protobuf::uint8* grSim_Robot_Command::SerializeWithCachedSizesToArray(
- ::google::protobuf::uint8* target) const {
+::google::protobuf::uint8* grSim_Robot_Command::InternalSerializeWithCachedSizesToArray(
+ bool deterministic, ::google::protobuf::uint8* target) const {
+ (void)deterministic; // Unused
+ // @@protoc_insertion_point(serialize_to_array_start:grSim_Robot_Command)
// required uint32 id = 1;
if (has_id()) {
target = ::google::protobuf::internal::WireFormatLite::WriteUInt32ToArray(1, this->id(), target);
@@ -579,61 +568,102 @@ ::google::protobuf::uint8* grSim_Robot_Command::SerializeWithCachedSizesToArray(
target = ::google::protobuf::internal::WireFormatLite::WriteFloatToArray(12, this->wheel4(), target);
}
- if (!unknown_fields().empty()) {
+ if (_internal_metadata_.have_unknown_fields()) {
target = ::google::protobuf::internal::WireFormat::SerializeUnknownFieldsToArray(
unknown_fields(), target);
}
+ // @@protoc_insertion_point(serialize_to_array_end:grSim_Robot_Command)
return target;
}
-int grSim_Robot_Command::ByteSize() const {
- int total_size = 0;
+size_t grSim_Robot_Command::RequiredFieldsByteSizeFallback() const {
+// @@protoc_insertion_point(required_fields_byte_size_fallback_start:grSim_Robot_Command)
+ size_t total_size = 0;
- if (_has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+ if (has_id()) {
// required uint32 id = 1;
- if (has_id()) {
- total_size += 1 +
- ::google::protobuf::internal::WireFormatLite::UInt32Size(
- this->id());
- }
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::UInt32Size(
+ this->id());
+ }
+ if (has_kickspeedx()) {
// required float kickspeedx = 2;
- if (has_kickspeedx()) {
- total_size += 1 + 4;
- }
+ total_size += 1 + 4;
+ }
+ if (has_kickspeedz()) {
// required float kickspeedz = 3;
- if (has_kickspeedz()) {
- total_size += 1 + 4;
- }
+ total_size += 1 + 4;
+ }
+ if (has_veltangent()) {
// required float veltangent = 4;
- if (has_veltangent()) {
- total_size += 1 + 4;
- }
+ total_size += 1 + 4;
+ }
+ if (has_velnormal()) {
// required float velnormal = 5;
- if (has_velnormal()) {
- total_size += 1 + 4;
- }
+ total_size += 1 + 4;
+ }
+ if (has_velangular()) {
// required float velangular = 6;
- if (has_velangular()) {
- total_size += 1 + 4;
- }
+ total_size += 1 + 4;
+ }
+ if (has_spinner()) {
// required bool spinner = 7;
- if (has_spinner()) {
- total_size += 1 + 1;
- }
+ total_size += 1 + 1;
+ }
+ if (has_wheelsspeed()) {
// required bool wheelsspeed = 8;
- if (has_wheelsspeed()) {
- total_size += 1 + 1;
- }
+ total_size += 1 + 1;
+ }
+
+ return total_size;
+}
+size_t grSim_Robot_Command::ByteSizeLong() const {
+// @@protoc_insertion_point(message_byte_size_start:grSim_Robot_Command)
+ size_t total_size = 0;
+
+ if (_internal_metadata_.have_unknown_fields()) {
+ total_size +=
+ ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
+ unknown_fields());
+ }
+ if (((_has_bits_[0] & 0x000000ff) ^ 0x000000ff) == 0) { // All required fields are present.
+ // required uint32 id = 1;
+ total_size += 1 +
+ ::google::protobuf::internal::WireFormatLite::UInt32Size(
+ this->id());
+
+ // required float kickspeedx = 2;
+ total_size += 1 + 4;
+
+ // required float kickspeedz = 3;
+ total_size += 1 + 4;
+
+ // required float veltangent = 4;
+ total_size += 1 + 4;
+
+ // required float velnormal = 5;
+ total_size += 1 + 4;
+
+ // required float velangular = 6;
+ total_size += 1 + 4;
+
+ // required bool spinner = 7;
+ total_size += 1 + 1;
+
+ // required bool wheelsspeed = 8;
+ total_size += 1 + 1;
+ } else {
+ total_size += RequiredFieldsByteSizeFallback();
}
- if (_has_bits_[8 / 32] & (0xffu << (8 % 32))) {
+ if (_has_bits_[8 / 32] & 3840u) {
// optional float wheel1 = 9;
if (has_wheel1()) {
total_size += 1 + 4;
@@ -655,32 +685,33 @@ int grSim_Robot_Command::ByteSize() const {
}
}
- if (!unknown_fields().empty()) {
- total_size +=
- ::google::protobuf::internal::WireFormat::ComputeUnknownFieldsSize(
- unknown_fields());
- }
+ int cached_size = ::google::protobuf::internal::ToCachedSize(total_size);
GOOGLE_SAFE_CONCURRENT_WRITES_BEGIN();
- _cached_size_ = total_size;
+ _cached_size_ = cached_size;
GOOGLE_SAFE_CONCURRENT_WRITES_END();
return total_size;
}
void grSim_Robot_Command::MergeFrom(const ::google::protobuf::Message& from) {
- GOOGLE_CHECK_NE(&from, this);
+// @@protoc_insertion_point(generalized_merge_from_start:grSim_Robot_Command)
+ GOOGLE_DCHECK_NE(&from, this);
const grSim_Robot_Command* source =
- ::google::protobuf::internal::dynamic_cast_if_available(
- &from);
+ ::google::protobuf::internal::DynamicCastToGenerated(
+ &from);
if (source == NULL) {
+ // @@protoc_insertion_point(generalized_merge_from_cast_fail:grSim_Robot_Command)
::google::protobuf::internal::ReflectionOps::Merge(from, this);
} else {
+ // @@protoc_insertion_point(generalized_merge_from_cast_success:grSim_Robot_Command)
MergeFrom(*source);
}
}
void grSim_Robot_Command::MergeFrom(const grSim_Robot_Command& from) {
- GOOGLE_CHECK_NE(&from, this);
- if (from._has_bits_[0 / 32] & (0xffu << (0 % 32))) {
+// @@protoc_insertion_point(class_specific_merge_from_start:grSim_Robot_Command)
+ GOOGLE_DCHECK_NE(&from, this);
+ _internal_metadata_.MergeFrom(from._internal_metadata_);
+ if (from._has_bits_[0 / 32] & 255u) {
if (from.has_id()) {
set_id(from.id());
}
@@ -706,7 +737,7 @@ void grSim_Robot_Command::MergeFrom(const grSim_Robot_Command& from) {
set_wheelsspeed(from.wheelsspeed());
}
}
- if (from._has_bits_[8 / 32] & (0xffu << (8 % 32))) {
+ if (from._has_bits_[8 / 32] & 3840u) {
if (from.has_wheel1()) {
set_wheel1(from.wheel1());
}
@@ -720,16 +751,17 @@ void grSim_Robot_Command::MergeFrom(const grSim_Robot_Command& from) {
set_wheel4(from.wheel4());
}
}
- mutable_unknown_fields()->MergeFrom(from.unknown_fields());
}
void grSim_Robot_Command::CopyFrom(const ::google::protobuf::Message& from) {
+// @@protoc_insertion_point(generalized_copy_from_start:grSim_Robot_Command)
if (&from == this) return;
Clear();
MergeFrom(from);
}
void grSim_Robot_Command::CopyFrom(const grSim_Robot_Command& from) {
+// @@protoc_insertion_point(class_specific_copy_from_start:grSim_Robot_Command)
if (&from == this) return;
Clear();
MergeFrom(from);
@@ -737,75 +769,370 @@ void grSim_Robot_Command::CopyFrom(const grSim_Robot_Command& from) {
bool grSim_Robot_Command::IsInitialized() const {
if ((_has_bits_[0] & 0x000000ff) != 0x000000ff) return false;
-
return true;
}
void grSim_Robot_Command::Swap(grSim_Robot_Command* other) {
- if (other != this) {
- std::swap(id_, other->id_);
- std::swap(kickspeedx_, other->kickspeedx_);
- std::swap(kickspeedz_, other->kickspeedz_);
- std::swap(veltangent_, other->veltangent_);
- std::swap(velnormal_, other->velnormal_);
- std::swap(velangular_, other->velangular_);
- std::swap(spinner_, other->spinner_);
- std::swap(wheelsspeed_, other->wheelsspeed_);
- std::swap(wheel1_, other->wheel1_);
- std::swap(wheel2_, other->wheel2_);
- std::swap(wheel3_, other->wheel3_);
- std::swap(wheel4_, other->wheel4_);
- std::swap(_has_bits_[0], other->_has_bits_[0]);
- _unknown_fields_.Swap(&other->_unknown_fields_);
- std::swap(_cached_size_, other->_cached_size_);
- }
+ if (other == this) return;
+ InternalSwap(other);
+}
+void grSim_Robot_Command::InternalSwap(grSim_Robot_Command* other) {
+ std::swap(id_, other->id_);
+ std::swap(kickspeedx_, other->kickspeedx_);
+ std::swap(kickspeedz_, other->kickspeedz_);
+ std::swap(veltangent_, other->veltangent_);
+ std::swap(velnormal_, other->velnormal_);
+ std::swap(velangular_, other->velangular_);
+ std::swap(spinner_, other->spinner_);
+ std::swap(wheelsspeed_, other->wheelsspeed_);
+ std::swap(wheel1_, other->wheel1_);
+ std::swap(wheel2_, other->wheel2_);
+ std::swap(wheel3_, other->wheel3_);
+ std::swap(wheel4_, other->wheel4_);
+ std::swap(_has_bits_[0], other->_has_bits_[0]);
+ _internal_metadata_.Swap(&other->_internal_metadata_);
+ std::swap(_cached_size_, other->_cached_size_);
}
::google::protobuf::Metadata grSim_Robot_Command::GetMetadata() const {
protobuf_AssignDescriptorsOnce();
- ::google::protobuf::Metadata metadata;
- metadata.descriptor = grSim_Robot_Command_descriptor_;
- metadata.reflection = grSim_Robot_Command_reflection_;
- return metadata;
+ return file_level_metadata[0];
+}
+
+#if PROTOBUF_INLINE_NOT_IN_HEADERS
+// grSim_Robot_Command
+
+// required uint32 id = 1;
+bool grSim_Robot_Command::has_id() const {
+ return (_has_bits_[0] & 0x00000001u) != 0;
+}
+void grSim_Robot_Command::set_has_id() {
+ _has_bits_[0] |= 0x00000001u;
+}
+void grSim_Robot_Command::clear_has_id() {
+ _has_bits_[0] &= ~0x00000001u;
+}
+void grSim_Robot_Command::clear_id() {
+ id_ = 0u;
+ clear_has_id();
+}
+::google::protobuf::uint32 grSim_Robot_Command::id() const {
+ // @@protoc_insertion_point(field_get:grSim_Robot_Command.id)
+ return id_;
+}
+void grSim_Robot_Command::set_id(::google::protobuf::uint32 value) {
+ set_has_id();
+ id_ = value;
+ // @@protoc_insertion_point(field_set:grSim_Robot_Command.id)
}
+// required float kickspeedx = 2;
+bool grSim_Robot_Command::has_kickspeedx() const {
+ return (_has_bits_[0] & 0x00000002u) != 0;
+}
+void grSim_Robot_Command::set_has_kickspeedx() {
+ _has_bits_[0] |= 0x00000002u;
+}
+void grSim_Robot_Command::clear_has_kickspeedx() {
+ _has_bits_[0] &= ~0x00000002u;
+}
+void grSim_Robot_Command::clear_kickspeedx() {
+ kickspeedx_ = 0;
+ clear_has_kickspeedx();
+}
+float grSim_Robot_Command::kickspeedx() const {
+ // @@protoc_insertion_point(field_get:grSim_Robot_Command.kickspeedx)
+ return kickspeedx_;
+}
+void grSim_Robot_Command::set_kickspeedx(float value) {
+ set_has_kickspeedx();
+ kickspeedx_ = value;
+ // @@protoc_insertion_point(field_set:grSim_Robot_Command.kickspeedx)
+}
+
+// required float kickspeedz = 3;
+bool grSim_Robot_Command::has_kickspeedz() const {
+ return (_has_bits_[0] & 0x00000004u) != 0;
+}
+void grSim_Robot_Command::set_has_kickspeedz() {
+ _has_bits_[0] |= 0x00000004u;
+}
+void grSim_Robot_Command::clear_has_kickspeedz() {
+ _has_bits_[0] &= ~0x00000004u;
+}
+void grSim_Robot_Command::clear_kickspeedz() {
+ kickspeedz_ = 0;
+ clear_has_kickspeedz();
+}
+float grSim_Robot_Command::kickspeedz() const {
+ // @@protoc_insertion_point(field_get:grSim_Robot_Command.kickspeedz)
+ return kickspeedz_;
+}
+void grSim_Robot_Command::set_kickspeedz(float value) {
+ set_has_kickspeedz();
+ kickspeedz_ = value;
+ // @@protoc_insertion_point(field_set:grSim_Robot_Command.kickspeedz)
+}
+
+// required float veltangent = 4;
+bool grSim_Robot_Command::has_veltangent() const {
+ return (_has_bits_[0] & 0x00000008u) != 0;
+}
+void grSim_Robot_Command::set_has_veltangent() {
+ _has_bits_[0] |= 0x00000008u;
+}
+void grSim_Robot_Command::clear_has_veltangent() {
+ _has_bits_[0] &= ~0x00000008u;
+}
+void grSim_Robot_Command::clear_veltangent() {
+ veltangent_ = 0;
+ clear_has_veltangent();
+}
+float grSim_Robot_Command::veltangent() const {
+ // @@protoc_insertion_point(field_get:grSim_Robot_Command.veltangent)
+ return veltangent_;
+}
+void grSim_Robot_Command::set_veltangent(float value) {
+ set_has_veltangent();
+ veltangent_ = value;
+ // @@protoc_insertion_point(field_set:grSim_Robot_Command.veltangent)
+}
+
+// required float velnormal = 5;
+bool grSim_Robot_Command::has_velnormal() const {
+ return (_has_bits_[0] & 0x00000010u) != 0;
+}
+void grSim_Robot_Command::set_has_velnormal() {
+ _has_bits_[0] |= 0x00000010u;
+}
+void grSim_Robot_Command::clear_has_velnormal() {
+ _has_bits_[0] &= ~0x00000010u;
+}
+void grSim_Robot_Command::clear_velnormal() {
+ velnormal_ = 0;
+ clear_has_velnormal();
+}
+float grSim_Robot_Command::velnormal() const {
+ // @@protoc_insertion_point(field_get:grSim_Robot_Command.velnormal)
+ return velnormal_;
+}
+void grSim_Robot_Command::set_velnormal(float value) {
+ set_has_velnormal();
+ velnormal_ = value;
+ // @@protoc_insertion_point(field_set:grSim_Robot_Command.velnormal)
+}
+
+// required float velangular = 6;
+bool grSim_Robot_Command::has_velangular() const {
+ return (_has_bits_[0] & 0x00000020u) != 0;
+}
+void grSim_Robot_Command::set_has_velangular() {
+ _has_bits_[0] |= 0x00000020u;
+}
+void grSim_Robot_Command::clear_has_velangular() {
+ _has_bits_[0] &= ~0x00000020u;
+}
+void grSim_Robot_Command::clear_velangular() {
+ velangular_ = 0;
+ clear_has_velangular();
+}
+float grSim_Robot_Command::velangular() const {
+ // @@protoc_insertion_point(field_get:grSim_Robot_Command.velangular)
+ return velangular_;
+}
+void grSim_Robot_Command::set_velangular(float value) {
+ set_has_velangular();
+ velangular_ = value;
+ // @@protoc_insertion_point(field_set:grSim_Robot_Command.velangular)
+}
+
+// required bool spinner = 7;
+bool grSim_Robot_Command::has_spinner() const {
+ return (_has_bits_[0] & 0x00000040u) != 0;
+}
+void grSim_Robot_Command::set_has_spinner() {
+ _has_bits_[0] |= 0x00000040u;
+}
+void grSim_Robot_Command::clear_has_spinner() {
+ _has_bits_[0] &= ~0x00000040u;
+}
+void grSim_Robot_Command::clear_spinner() {
+ spinner_ = false;
+ clear_has_spinner();
+}
+bool grSim_Robot_Command::spinner() const {
+ // @@protoc_insertion_point(field_get:grSim_Robot_Command.spinner)
+ return spinner_;
+}
+void grSim_Robot_Command::set_spinner(bool value) {
+ set_has_spinner();
+ spinner_ = value;
+ // @@protoc_insertion_point(field_set:grSim_Robot_Command.spinner)
+}
+
+// required bool wheelsspeed = 8;
+bool grSim_Robot_Command::has_wheelsspeed() const {
+ return (_has_bits_[0] & 0x00000080u) != 0;
+}
+void grSim_Robot_Command::set_has_wheelsspeed() {
+ _has_bits_[0] |= 0x00000080u;
+}
+void grSim_Robot_Command::clear_has_wheelsspeed() {
+ _has_bits_[0] &= ~0x00000080u;
+}
+void grSim_Robot_Command::clear_wheelsspeed() {
+ wheelsspeed_ = false;
+ clear_has_wheelsspeed();
+}
+bool grSim_Robot_Command::wheelsspeed() const {
+ // @@protoc_insertion_point(field_get:grSim_Robot_Command.wheelsspeed)
+ return wheelsspeed_;
+}
+void grSim_Robot_Command::set_wheelsspeed(bool value) {
+ set_has_wheelsspeed();
+ wheelsspeed_ = value;
+ // @@protoc_insertion_point(field_set:grSim_Robot_Command.wheelsspeed)
+}
+
+// optional float wheel1 = 9;
+bool grSim_Robot_Command::has_wheel1() const {
+ return (_has_bits_[0] & 0x00000100u) != 0;
+}
+void grSim_Robot_Command::set_has_wheel1() {
+ _has_bits_[0] |= 0x00000100u;
+}
+void grSim_Robot_Command::clear_has_wheel1() {
+ _has_bits_[0] &= ~0x00000100u;
+}
+void grSim_Robot_Command::clear_wheel1() {
+ wheel1_ = 0;
+ clear_has_wheel1();
+}
+float grSim_Robot_Command::wheel1() const {
+ // @@protoc_insertion_point(field_get:grSim_Robot_Command.wheel1)
+ return wheel1_;
+}
+void grSim_Robot_Command::set_wheel1(float value) {
+ set_has_wheel1();
+ wheel1_ = value;
+ // @@protoc_insertion_point(field_set:grSim_Robot_Command.wheel1)
+}
+
+// optional float wheel2 = 10;
+bool grSim_Robot_Command::has_wheel2() const {
+ return (_has_bits_[0] & 0x00000200u) != 0;
+}
+void grSim_Robot_Command::set_has_wheel2() {
+ _has_bits_[0] |= 0x00000200u;
+}
+void grSim_Robot_Command::clear_has_wheel2() {
+ _has_bits_[0] &= ~0x00000200u;
+}
+void grSim_Robot_Command::clear_wheel2() {
+ wheel2_ = 0;
+ clear_has_wheel2();
+}
+float grSim_Robot_Command::wheel2() const {
+ // @@protoc_insertion_point(field_get:grSim_Robot_Command.wheel2)
+ return wheel2_;
+}
+void grSim_Robot_Command::set_wheel2(float value) {
+ set_has_wheel2();
+ wheel2_ = value;
+ // @@protoc_insertion_point(field_set:grSim_Robot_Command.wheel2)
+}
+
+// optional float wheel3 = 11;
+bool grSim_Robot_Command::has_wheel3() const {
+ return (_has_bits_[0] & 0x00000400u) != 0;
+}
+void grSim_Robot_Command::set_has_wheel3() {
+ _has_bits_[0] |= 0x00000400u;
+}
+void grSim_Robot_Command::clear_has_wheel3() {
+ _has_bits_[0] &= ~0x00000400u;
+}
+void grSim_Robot_Command::clear_wheel3() {
+ wheel3_ = 0;
+ clear_has_wheel3();
+}
+float grSim_Robot_Command::wheel3() const {
+ // @@protoc_insertion_point(field_get:grSim_Robot_Command.wheel3)
+ return wheel3_;
+}
+void grSim_Robot_Command::set_wheel3(float value) {
+ set_has_wheel3();
+ wheel3_ = value;
+ // @@protoc_insertion_point(field_set:grSim_Robot_Command.wheel3)
+}
+
+// optional float wheel4 = 12;
+bool grSim_Robot_Command::has_wheel4() const {
+ return (_has_bits_[0] & 0x00000800u) != 0;
+}
+void grSim_Robot_Command::set_has_wheel4() {
+ _has_bits_[0] |= 0x00000800u;
+}
+void grSim_Robot_Command::clear_has_wheel4() {
+ _has_bits_[0] &= ~0x00000800u;
+}
+void grSim_Robot_Command::clear_wheel4() {
+ wheel4_ = 0;
+ clear_has_wheel4();
+}
+float grSim_Robot_Command::wheel4() const {
+ // @@protoc_insertion_point(field_get:grSim_Robot_Command.wheel4)
+ return wheel4_;
+}
+void grSim_Robot_Command::set_wheel4(float value) {
+ set_has_wheel4();
+ wheel4_ = value;
+ // @@protoc_insertion_point(field_set:grSim_Robot_Command.wheel4)
+}
+
+#endif // PROTOBUF_INLINE_NOT_IN_HEADERS
// ===================================================================
-#ifndef _MSC_VER
+#if !defined(_MSC_VER) || _MSC_VER >= 1900
const int grSim_Commands::kTimestampFieldNumber;
const int grSim_Commands::kIsteamyellowFieldNumber;
const int grSim_Commands::kRobotCommandsFieldNumber;
-#endif // !_MSC_VER
+#endif // !defined(_MSC_VER) || _MSC_VER >= 1900
grSim_Commands::grSim_Commands()
- : ::google::protobuf::Message() {
+ : ::google::protobuf::Message(), _internal_metadata_(NULL) {
+ if (GOOGLE_PREDICT_TRUE(this != internal_default_instance())) {
+ protobuf_InitDefaults_grSim_5fCommands_2eproto();
+ }
SharedCtor();
+ // @@protoc_insertion_point(constructor:grSim_Commands)
}
-
-void grSim_Commands::InitAsDefaultInstance() {
-}
-
grSim_Commands::grSim_Commands(const grSim_Commands& from)
- : ::google::protobuf::Message() {
- SharedCtor();
- MergeFrom(from);
+ : ::google::protobuf::Message(),
+ _internal_metadata_(NULL),
+ _has_bits_(from._has_bits_),
+ _cached_size_(0),
+ robot_commands_(from.robot_commands_) {
+ _internal_metadata_.MergeFrom(from._internal_metadata_);
+ ::memcpy(×tamp_, &from.timestamp_,
+ reinterpret_cast(&isteamyellow_) -
+ reinterpret_cast(×tamp_) + sizeof(isteamyellow_));
+ // @@protoc_insertion_point(copy_constructor:grSim_Commands)
}
void grSim_Commands::SharedCtor() {
_cached_size_ = 0;
- timestamp_ = 0;
- isteamyellow_ = false;
- ::memset(_has_bits_, 0, sizeof(_has_bits_));
+ ::memset(×tamp_, 0, reinterpret_cast