Decision Module  1.0
ICRA2020 AI Challenge Northwestern Polytechnical University Aoxiang Team Strategy Code
prediction_system.h
Go to the documentation of this file.
1 //
2 // Created by wpy on 2020/8/5.
3 //
4 
5 #ifndef ROBOTRTS_WS_SRC_ICRA_FIREFLY_ROBORTS_ROBORTS_DECISION_BLACKBOARD_PREDICTION_SYSTEM_H_
6 #define ROBOTRTS_WS_SRC_ICRA_FIREFLY_ROBORTS_ROBORTS_DECISION_BLACKBOARD_PREDICTION_SYSTEM_H_
7 
11 #include "my_robot.h"
12 #include "enemy_robot.h"
13 #include "field.h"
14 
15 namespace roborts_decision {
17  public:
18 
19  PredictionSystem(std::shared_ptr<MyRobot> p_my_robot_1,std::shared_ptr<MyRobot> p_my_robot_2, EnemyRobot &enemy_robot_1 ,EnemyRobot &enemy_robot_2);
20 
21  PredictionSystem() = delete ;
22  ~PredictionSystem() = default;
23 
24 
25  // 获取剩余子弹数
27 
28  // 获得剩余血量
29  void UpdatePredictedHp();
30 
31  // 获得枪口热量
33 
34  // 获取当前敌方子弹buff状态
36 
37  // 获取当前敌方血量buff状态
39 
40  // 预测敌方打击我方的机器人
41  std::vector<roborts_decision::EnemyRobot> PredictWhoAttackHome(const std::shared_ptr<roborts_decision::MyRobot> &p_my_robot);
42  private:
43 
44  std::shared_ptr<MyRobot> p_my_robot_1_;
45  std::shared_ptr<MyRobot> p_my_robot_2_;
46  std::array<std::shared_ptr<MyRobot>, 2> all_home_;
47 
48  std::shared_ptr<Field> field_;
49 
56 
61 
62  // 根据距离预测敌方可能发射的子弹
63  int PredictBulletNumbersWithDistance(const roborts_common::Point2D &pose_1, const roborts_common::Point2D &pose_2);
64 
65  int PredictSpeedWithDistance(const roborts_common::Point2D &pose_1, const roborts_common::Point2D &pose_2);
66 
67  int PredictDamageToEnemyWithBullets(const int bullets);
68 
69  void NormalizedEnemyAttacker(std::vector<roborts_decision::EnemyRobot> &enemy_to_attack_home_1, std::vector<roborts_decision::EnemyRobot>&enemy_to_attack_home_2);
70 
71 };
72 }
73 #endif //ROBOTRTS_WS_SRC_ICRA_FIREFLY_ROBORTS_ROBORTS_DECISION_BLACKBOARD_PREDICTION_SYSTEM_H_
roborts_decision::PredictionSystem::field_
std::shared_ptr< Field > field_
Definition: prediction_system.h:48
roborts_decision::PredictionSystem::UpdatePredictedHp
void UpdatePredictedHp()
Definition: prediction_system.cpp:84
roborts_decision::PredictionSystem::PredictSpeedWithDistance
int PredictSpeedWithDistance(const roborts_common::Point2D &pose_1, const roborts_common::Point2D &pose_2)
Definition: prediction_system.cpp:293
roborts_decision::PredictionSystem::enemy_robot_1_
EnemyRobot & enemy_robot_1_
Definition: prediction_system.h:50
enemy_robot.h
roborts_decision::PredictionSystem::~PredictionSystem
~PredictionSystem()=default
roborts_decision::PredictionSystem::bullet_shoot_enemy_2_to_home_2_
int bullet_shoot_enemy_2_to_home_2_
Definition: prediction_system.h:55
roborts_decision::PredictionSystem::bullet_shoot_enemy_1_to_home_1_
int bullet_shoot_enemy_1_to_home_1_
Definition: prediction_system.h:52
roborts_decision::PredictionSystem::GetEnemyBulletBuffStatus
bool GetEnemyBulletBuffStatus()
Definition: prediction_system.cpp:187
roborts_decision::PredictionSystem::speed_shoot_enemy_2_to_home_2_
int speed_shoot_enemy_2_to_home_2_
Definition: prediction_system.h:60
roborts_decision::PredictionSystem::PredictWhoAttackHome
std::vector< roborts_decision::EnemyRobot > PredictWhoAttackHome(const std::shared_ptr< roborts_decision::MyRobot > &p_my_robot)
Definition: prediction_system.cpp:215
roborts_decision::PredictionSystem::PredictBulletNumbersWithDistance
int PredictBulletNumbersWithDistance(const roborts_common::Point2D &pose_1, const roborts_common::Point2D &pose_2)
Definition: prediction_system.cpp:274
roborts_decision::PredictionSystem::NormalizedEnemyAttacker
void NormalizedEnemyAttacker(std::vector< roborts_decision::EnemyRobot > &enemy_to_attack_home_1, std::vector< roborts_decision::EnemyRobot > &enemy_to_attack_home_2)
Definition: prediction_system.cpp:317
roborts_decision::PredictionSystem::p_my_robot_1_
std::shared_ptr< MyRobot > p_my_robot_1_
Definition: prediction_system.h:44
roborts_decision::PredictionSystem
Definition: prediction_system.h:16
roborts_decision::PredictionSystem::GetEnemyBloodBuffStatus
bool GetEnemyBloodBuffStatus()
Definition: prediction_system.cpp:201
my_robot.h
roborts_decision::PredictionSystem::speed_shoot_enemy_1_to_home_2_
int speed_shoot_enemy_1_to_home_2_
Definition: prediction_system.h:58
field.h
roborts_decision
Definition: behavior_test_node.h:14
roborts_decision::PredictionSystem::speed_shoot_enemy_1_to_home_1_
int speed_shoot_enemy_1_to_home_1_
Definition: prediction_system.h:57
roborts_decision::PredictionSystem::PredictDamageToEnemyWithBullets
int PredictDamageToEnemyWithBullets(const int bullets)
Definition: prediction_system.cpp:402
roborts_decision::PredictionSystem::all_home_
std::array< std::shared_ptr< MyRobot >, 2 > all_home_
Definition: prediction_system.h:46
roborts_decision::PredictionSystem::UpdatePredictedRemainingProjectiles
void UpdatePredictedRemainingProjectiles()
Definition: prediction_system.cpp:29
roborts_decision::PredictionSystem::PredictionSystem
PredictionSystem()=delete
roborts_decision::PredictionSystem::enemy_robot_2_
EnemyRobot & enemy_robot_2_
Definition: prediction_system.h:51
roborts_decision::PredictionSystem::bullet_shoot_enemy_2_to_home_1_
int bullet_shoot_enemy_2_to_home_1_
Definition: prediction_system.h:54
roborts_decision::PredictionSystem::p_my_robot_2_
std::shared_ptr< MyRobot > p_my_robot_2_
Definition: prediction_system.h:45
roborts_decision::PredictionSystem::bullet_shoot_enemy_1_to_home_2_
int bullet_shoot_enemy_1_to_home_2_
Definition: prediction_system.h:53
roborts_decision::PredictionSystem::UpdatePredictedCurrentHeat
void UpdatePredictedCurrentHeat()
Definition: prediction_system.cpp:128
roborts_decision::PredictionSystem::speed_shoot_enemy_2_to_home_1_
int speed_shoot_enemy_2_to_home_1_
Definition: prediction_system.h:59
roborts_decision::EnemyRobot
Definition: enemy_robot.h:16