Decision Module
1.0
ICRA2020 AI Challenge Northwestern Polytechnical University Aoxiang Team Strategy Code
|
Go to the documentation of this file.
5 #ifndef SRC_ATTACK_AND_SURVIVAL_H
6 #define SRC_ATTACK_AND_SURVIVAL_H
8 #include "../behavior/robot_behaviors.h"
19 std::shared_ptr<Blackboard> p_blackboard,
32 ROS_ERROR(
"The Zone is not active! id %d", 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;
51 for (
auto buffZoneStatus :
p_blackboard_->GetBuffZoneStatus()) {
56 }
else if (buffZoneStatus.first.is_active_ &&
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();
82 auto current_behavior =
p_my_robot1->GetCurrentBehavior();
83 if (current_behavior !=
CHASE) {
88 current_behavior =
p_my_robot2->GetCurrentBehavior();
89 if (current_behavior !=
GOAL) {
98 auto current_behavior =
p_my_robot2->GetCurrentBehavior();
99 if (current_behavior !=
CHASE) {
104 current_behavior =
p_my_robot1->GetCurrentBehavior();
105 if (current_behavior !=
GOAL) {
115 auto current_behavior =
p_my_robot1->GetCurrentBehavior();
116 if (current_behavior !=
CHASE) {
121 current_behavior =
p_my_robot2->GetCurrentBehavior();
122 if (current_behavior !=
GOAL) {
131 auto current_behavior =
p_my_robot2->GetCurrentBehavior();
132 if (current_behavior !=
CHASE) {
137 current_behavior =
p_my_robot1->GetCurrentBehavior();
138 if (current_behavior !=
GOAL) {
161 #endif //SRC_ATTACK_AND_SURVIVAL_H
void taskAllocation(AASType aasType)
Definition: attack_and_survival.h:76
@ FIND_PROJECTILE
Definition: attack_and_survival.h:12
@ RED_RESTORATION
Definition: blackboard_common.h:62
@ SUPPLY
Definition: blackboard_common.h:51
std::shared_ptr< MyRobot > p_my_robot1
Definition: attack_and_survival.h:152
@ ESCAPE
Definition: blackboard_common.h:49
std::shared_ptr< Blackboard > p_blackboard_
Definition: attack_and_survival.h:154
std::shared_ptr< RobotBehaviors > p_attack_robot_behavior
Definition: attack_and_survival.h:155
std::shared_ptr< RobotBehaviors > p_robot1_behaviors
Definition: attack_and_survival.h:157
@ CHASE
Definition: blackboard_common.h:48
int getSupplyId(AASType aasType)
Definition: attack_and_survival.h:49
void run(AASType aasType)
Definition: attack_and_survival.h:29
Definition: attack_and_survival.h:15
@ RED_PROJECTILE_SUPPLIER
Definition: blackboard_common.h:63
Definition: behavior_test_node.h:14
@ GOAL
Definition: blackboard_common.h:50
static void CancelBehavior(const std::shared_ptr< MyRobot > &myRobot, const std::shared_ptr< RobotBehaviors > &robotBehaviors)
Definition: attack_and_survival.h:64
std::shared_ptr< RobotBehaviors > p_survival_robot_behavior
Definition: attack_and_survival.h:156
std::shared_ptr< RobotBehaviors > p_robot2_behaviors
Definition: attack_and_survival.h:158
AASType
Definition: attack_and_survival.h:10
@ FIND_RESTORATION
Definition: attack_and_survival.h:11
std::shared_ptr< MyRobot > p_my_robot2
Definition: attack_and_survival.h:153
geometry_msgs::PoseStamped getGalPose(int supplyId)
Definition: attack_and_survival.h:40
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
void cancel()
Definition: attack_and_survival.h:146