Decision Module  1.0
ICRA2020 AI Challenge Northwestern Polytechnical University Aoxiang Team Strategy Code
attack_and_survival.h
Go to the documentation of this file.
1 //
2 // Created by noorall on 2020/4/12.
3 //
4 
5 #ifndef SRC_ATTACK_AND_SURVIVAL_H
6 #define SRC_ATTACK_AND_SURVIVAL_H
7 
8 #include "../behavior/robot_behaviors.h"
9 
10 enum AASType {
13 };
14 namespace roborts_decision {
16  public:
17  AttackAndSurvival(std::shared_ptr<MyRobot> p_my_robot1,
18  std::shared_ptr<MyRobot> p_my_robot2,
19  std::shared_ptr<Blackboard> p_blackboard,
20  std::shared_ptr<RobotBehaviors> p_robot1_behaviors,
21  std::shared_ptr<RobotBehaviors> p_robot2_behaviors) :
22  p_my_robot1(std::move(p_my_robot1)),
23  p_my_robot2(std::move(p_my_robot2)),
24  p_blackboard_(std::move(p_blackboard)),
27  }
28 
29  void run(AASType aasType) {
30  int supplyId = getSupplyId(aasType);
31  if (!supplyId) {
32  ROS_ERROR("The Zone is not active! id %d", supplyId);
33  } else {
34  taskAllocation(aasType);
35  p_attack_robot_behavior->GetPursueAttackBehavior()->Run(p_blackboard_->GetEnemyRobot1().GetId(), 1.2);
36  p_survival_robot_behavior->GetGoalBehavior()->Run(getGalPose(supplyId));
37  }
38  }
39 
40  geometry_msgs::PoseStamped getGalPose(int supplyId) {
41  geometry_msgs::PoseStamped galPose;
42  galPose.pose.orientation.z = 1;
43  galPose.pose.position.x = p_blackboard_->GetBuffZoneStatus().at(supplyId).second.zone_x_;
44  galPose.pose.position.y = p_blackboard_->GetBuffZoneStatus().at(supplyId).second.zone_y_;
45  galPose.pose.position.z = 0;
46  return galPose;
47  }
48 
49  int getSupplyId(AASType aasType) {
50  int supplyId = -1;
51  for (auto buffZoneStatus : p_blackboard_->GetBuffZoneStatus()) {
52  supplyId++;
53  if (aasType == FIND_RESTORATION && buffZoneStatus.first.is_active_ &&
54  buffZoneStatus.first.buff_status_ == RED_RESTORATION) {
55  return supplyId;
56  } else if (buffZoneStatus.first.is_active_ &&
57  buffZoneStatus.first.buff_status_ == RED_PROJECTILE_SUPPLIER) {
58  return supplyId;
59  }
60  }
61  return 0;
62  }
63 
64  static void CancelBehavior(const std::shared_ptr<MyRobot> &myRobot,
65  const std::shared_ptr<RobotBehaviors> &robotBehaviors) {
66  auto current_behavior = myRobot->GetCurrentBehavior();
67  if (current_behavior == ESCAPE) {
68  robotBehaviors->GetEscapeBehavior()->Cancel();
69  } else if (current_behavior == SUPPLY) {
70  robotBehaviors->GetSupplyBehavior()->Cancel();
71  } else if (current_behavior == GOAL) {
72  robotBehaviors->GetGoalBehavior()->Cancel();
73  }
74  }
75 
76  void taskAllocation(AASType aasType) {
77  if (aasType == FIND_RESTORATION) {
78  if (p_my_robot1->GetHp() > p_my_robot2->GetHp()) {
81 
82  auto current_behavior = p_my_robot1->GetCurrentBehavior();
83  if (current_behavior != CHASE) {
85  p_my_robot1->SetCurrentBehavior(CHASE);
86  }
87 
88  current_behavior = p_my_robot2->GetCurrentBehavior();
89  if (current_behavior != GOAL) {
91  p_my_robot1->SetCurrentBehavior(GOAL);
92  }
93 
94  } else {
97 
98  auto current_behavior = p_my_robot2->GetCurrentBehavior();
99  if (current_behavior != CHASE) {
101  p_my_robot2->SetCurrentBehavior(CHASE);
102  }
103 
104  current_behavior = p_my_robot1->GetCurrentBehavior();
105  if (current_behavior != GOAL) {
107  p_my_robot1->SetCurrentBehavior(GOAL);
108  }
109  }
110  } else {
111  if (p_my_robot1->GetRemainingProjectiles() > p_my_robot2->GetRemainingProjectiles()) {
114 
115  auto current_behavior = p_my_robot1->GetCurrentBehavior();
116  if (current_behavior != CHASE) {
118  p_my_robot1->SetCurrentBehavior(CHASE);
119  }
120 
121  current_behavior = p_my_robot2->GetCurrentBehavior();
122  if (current_behavior != GOAL) {
124  p_my_robot2->SetCurrentBehavior(GOAL);
125  }
126 
127  } else {
130 
131  auto current_behavior = p_my_robot2->GetCurrentBehavior();
132  if (current_behavior != CHASE) {
134  p_my_robot2->SetCurrentBehavior(CHASE);
135  }
136 
137  current_behavior = p_my_robot1->GetCurrentBehavior();
138  if (current_behavior != GOAL) {
140  p_my_robot1->SetCurrentBehavior(GOAL);
141  }
142  }
143  }
144  }
145 
146  void cancel() {
147  p_attack_robot_behavior->GetPursueAttackBehavior()->Cancel();
148  p_survival_robot_behavior->GetSupplyBehavior()->Cancel();
149  }
150 
151  private:
152  std::shared_ptr<MyRobot> p_my_robot1;
153  std::shared_ptr<MyRobot> p_my_robot2;
154  std::shared_ptr<Blackboard> p_blackboard_;
155  std::shared_ptr<RobotBehaviors> p_attack_robot_behavior;
156  std::shared_ptr<RobotBehaviors> p_survival_robot_behavior;
157  std::shared_ptr<RobotBehaviors> p_robot1_behaviors;
158  std::shared_ptr<RobotBehaviors> p_robot2_behaviors;
159 };
160 }
161 #endif //SRC_ATTACK_AND_SURVIVAL_H
roborts_decision::AttackAndSurvival::taskAllocation
void taskAllocation(AASType aasType)
Definition: attack_and_survival.h:76
FIND_PROJECTILE
@ FIND_PROJECTILE
Definition: attack_and_survival.h:12
roborts_decision::RED_RESTORATION
@ RED_RESTORATION
Definition: blackboard_common.h:62
roborts_decision::SUPPLY
@ SUPPLY
Definition: blackboard_common.h:51
roborts_decision::AttackAndSurvival::p_my_robot1
std::shared_ptr< MyRobot > p_my_robot1
Definition: attack_and_survival.h:152
roborts_decision::ESCAPE
@ ESCAPE
Definition: blackboard_common.h:49
roborts_decision::AttackAndSurvival::p_blackboard_
std::shared_ptr< Blackboard > p_blackboard_
Definition: attack_and_survival.h:154
roborts_decision::AttackAndSurvival::p_attack_robot_behavior
std::shared_ptr< RobotBehaviors > p_attack_robot_behavior
Definition: attack_and_survival.h:155
roborts_decision::AttackAndSurvival::p_robot1_behaviors
std::shared_ptr< RobotBehaviors > p_robot1_behaviors
Definition: attack_and_survival.h:157
roborts_decision::CHASE
@ CHASE
Definition: blackboard_common.h:48
roborts_decision::AttackAndSurvival::getSupplyId
int getSupplyId(AASType aasType)
Definition: attack_and_survival.h:49
roborts_decision::AttackAndSurvival::run
void run(AASType aasType)
Definition: attack_and_survival.h:29
roborts_decision::AttackAndSurvival
Definition: attack_and_survival.h:15
roborts_decision::RED_PROJECTILE_SUPPLIER
@ RED_PROJECTILE_SUPPLIER
Definition: blackboard_common.h:63
roborts_decision
Definition: behavior_test_node.h:14
roborts_decision::GOAL
@ GOAL
Definition: blackboard_common.h:50
roborts_decision::AttackAndSurvival::CancelBehavior
static void CancelBehavior(const std::shared_ptr< MyRobot > &myRobot, const std::shared_ptr< RobotBehaviors > &robotBehaviors)
Definition: attack_and_survival.h:64
roborts_decision::AttackAndSurvival::p_survival_robot_behavior
std::shared_ptr< RobotBehaviors > p_survival_robot_behavior
Definition: attack_and_survival.h:156
roborts_decision::AttackAndSurvival::p_robot2_behaviors
std::shared_ptr< RobotBehaviors > p_robot2_behaviors
Definition: attack_and_survival.h:158
AASType
AASType
Definition: attack_and_survival.h:10
FIND_RESTORATION
@ FIND_RESTORATION
Definition: attack_and_survival.h:11
roborts_decision::AttackAndSurvival::p_my_robot2
std::shared_ptr< MyRobot > p_my_robot2
Definition: attack_and_survival.h:153
roborts_decision::AttackAndSurvival::getGalPose
geometry_msgs::PoseStamped getGalPose(int supplyId)
Definition: attack_and_survival.h:40
roborts_decision::AttackAndSurvival::AttackAndSurvival
AttackAndSurvival(std::shared_ptr< MyRobot > p_my_robot1, std::shared_ptr< MyRobot > p_my_robot2, std::shared_ptr< Blackboard > p_blackboard, std::shared_ptr< RobotBehaviors > p_robot1_behaviors, std::shared_ptr< RobotBehaviors > p_robot2_behaviors)
Definition: attack_and_survival.h:17
roborts_decision::AttackAndSurvival::cancel
void cancel()
Definition: attack_and_survival.h:146