Decision Module  1.0
ICRA2020 AI Challenge Northwestern Polytechnical University Aoxiang Team Strategy Code
enemy_robot.h
Go to the documentation of this file.
1 //
2 // Created by kehan on 2020/2/28.
3 //
4 
5 #ifndef ROBORTS_ROBORTS_DECISION_BLACKBOARD_ENEMY_ROBOT_H_
6 #define ROBORTS_ROBORTS_DECISION_BLACKBOARD_ENEMY_ROBOT_H_
7 
8 #include "../../roborts_common/math/math.h"
9 #include "blackboard_common.h"
10 #include <geometry_msgs/PoseStamped.h>
11 #include <nav_msgs/Odometry.h>
12 #include <roborts_msgs/ShootInfo.h>
13 #include <ros/ros.h>
14 
15 namespace roborts_decision {
16 class EnemyRobot {
17 public:
18  EnemyRobot(const RobotId &robot_id, MyColor my_color);
19  virtual ~EnemyRobot();
20  void Init();
21 
22  RobotId GetId() const;
23 
24  RobotType GetRobotType() const;
25  void SetRobotType(RobotType robot_type);
26 
27  void SetColor(MyColor color);
28  MyColor GetColor() const;
29 
30  bool IsSurvival() const;
31  void SetIsSurvival(bool is_survival);
32 
33  const geometry_msgs::PoseStamped &GetPose() const;
34  void SetPose(const ros::Time &stamp, const geometry_msgs::Point &position);
35 
36  // 获取剩余子弹数
37  int getRemainingProjectiles() const;
38  // 更新子弹数
39  void SetRemainingProjectiles(const int bullets);
40 
41  // 获得剩余血量
42  int getHp() const;
43  //设置当前血量
44  void SetHp(const int hp);
45 
46  // 获得枪口热量
47  int getCurrentHeat() const;
48  void SetCurrentHeat(const int heat);
49 
50  // 是否可移动
51  bool canMove() const;
52  bool SetCanMove(const bool canMove);
53 
54  // 是否可射击
55  bool canShoot() const;
56  void SetCanShoot(const bool canShoot);
57 
58  bool IsDetected() const;
59  void SetIsDetected(bool is_detected);
60 
61  // 获取敌方机器人的状态评估值
62  double getState() const;
63  double getStanderdState() const; // 一般状态阈值
64 
65  // 获得敌方机器人正向相对某点的偏角
66  double getRelativeAngle(roborts_common::Point2D point) const;
67 
68  // 获取敌方机器人的坐标,以Point2D形式返回
69  roborts_common::Point2D getEnemyPoint() const;
70 
71  // 获取敌方机器人当前位姿
72  Posture getCurrentPosture() const;
73 
74  // 设置敌方机器人射击参数,用于状态估计(getState)
76 
77  // 设置敌方机器人移动参数,用于状态估计(getState)
78  void SetEnemyMoveParameter();
79 
80  void EnemyRobotPoseCallback(const nav_msgs::Odometry::ConstPtr &msg);
81 
82 
83 
84  bool operator==(const EnemyRobot &e_r)const;
85 
86 private:
90 
91  ros::NodeHandle nh_;
92  ros::Subscriber enemy_pose_sub_;
93 
95  int hp_;
97  bool can_move_;
98  bool can_shoot_;
99 
102  geometry_msgs::PoseStamped pose_;
103 
104  // 状态评估的系数
105  constexpr static double kBlood = 0.9;
106  constexpr static double kBullet = 0.8;
107  constexpr static double kHeat = 0.1;
108  double tNoShoot = 0;
109  double tNoMove = 0;
110 };
111 } // namespace roborts_decision
112 
113 #endif // ROBORTS_ROBORTS_DECISION_BLACKBOARD_ENEMY_ROBOT_H_
roborts_decision::EnemyRobot::IsSurvival
bool IsSurvival() const
Definition: enemy_robot.cpp:69
roborts_decision::EnemyRobot::kBullet
constexpr static double kBullet
Definition: enemy_robot.h:106
roborts_decision::EnemyRobot::SetRemainingProjectiles
void SetRemainingProjectiles(const int bullets)
Definition: enemy_robot.cpp:140
roborts_decision::EnemyRobot::SetEnemyShootParameter
void SetEnemyShootParameter()
Definition: enemy_robot.cpp:204
dqn_decision_node.my_color
my_color
Definition: dqn_decision_node.py:14
roborts_decision::EnemyRobot::SetCanShoot
void SetCanShoot(const bool canShoot)
Definition: enemy_robot.cpp:176
roborts_decision::EnemyRobot::is_detected_
bool is_detected_
Definition: enemy_robot.h:101
roborts_decision::EnemyRobot::getCurrentPosture
Posture getCurrentPosture() const
Definition: enemy_robot.cpp:195
roborts_decision::EnemyRobot::GetPose
const geometry_msgs::PoseStamped & GetPose() const
Definition: enemy_robot.cpp:78
roborts_decision::EnemyRobot::GetRobotType
RobotType GetRobotType() const
Definition: enemy_robot.cpp:53
roborts_decision::EnemyRobot::GetId
RobotId GetId() const
Definition: enemy_robot.cpp:49
roborts_decision::EnemyRobot::can_move_
bool can_move_
Definition: enemy_robot.h:97
roborts_decision::EnemyRobot::kBlood
constexpr static double kBlood
Definition: enemy_robot.h:105
roborts_decision::EnemyRobot::getRemainingProjectiles
int getRemainingProjectiles() const
Definition: enemy_robot.cpp:137
roborts_decision::EnemyRobot::GetColor
MyColor GetColor() const
Definition: enemy_robot.cpp:65
roborts_decision::EnemyRobot::SetCanMove
bool SetCanMove(const bool canMove)
Definition: enemy_robot.cpp:167
roborts_decision::EnemyRobot::Init
void Init()
Definition: enemy_robot.cpp:16
roborts_decision::MyColor
MyColor
Definition: blackboard_common.h:96
roborts_decision::EnemyRobot::EnemyRobotPoseCallback
void EnemyRobotPoseCallback(const nav_msgs::Odometry::ConstPtr &msg)
Definition: enemy_robot.cpp:88
blackboard_common.h
roborts_decision::EnemyRobot::canShoot
bool canShoot() const
Definition: enemy_robot.cpp:172
roborts_decision::EnemyRobot::num_of_bullets_
int num_of_bullets_
Definition: enemy_robot.h:94
roborts_decision::EnemyRobot::color_
MyColor color_
Definition: enemy_robot.h:89
roborts_decision::EnemyRobot::getRelativeAngle
double getRelativeAngle(roborts_common::Point2D point) const
Definition: enemy_robot.cpp:180
roborts_decision::EnemyRobot::can_shoot_
bool can_shoot_
Definition: enemy_robot.h:98
roborts_decision::EnemyRobot::operator==
bool operator==(const EnemyRobot &e_r) const
Definition: enemy_robot.cpp:212
roborts_decision::EnemyRobot::SetRobotType
void SetRobotType(RobotType robot_type)
Definition: enemy_robot.cpp:57
roborts_decision::EnemyRobot::is_survival_
bool is_survival_
Definition: enemy_robot.h:100
roborts_decision::EnemyRobot::getCurrentHeat
int getCurrentHeat() const
Definition: enemy_robot.cpp:154
roborts_decision::EnemyRobot::getEnemyPoint
roborts_common::Point2D getEnemyPoint() const
Definition: enemy_robot.cpp:199
roborts_decision::EnemyRobot::tNoMove
double tNoMove
Definition: enemy_robot.h:109
roborts_decision::EnemyRobot::IsDetected
bool IsDetected() const
Definition: enemy_robot.cpp:107
roborts_decision::EnemyRobot::current_heat_
int current_heat_
Definition: enemy_robot.h:96
roborts_decision
Definition: behavior_test_node.h:14
roborts_decision::EnemyRobot::SetColor
void SetColor(MyColor color)
Definition: enemy_robot.cpp:61
roborts_decision::EnemyRobot::SetHp
void SetHp(const int hp)
Definition: enemy_robot.cpp:149
roborts_decision::RobotId
RobotId
Definition: blackboard_common.h:89
roborts_decision::EnemyRobot::~EnemyRobot
virtual ~EnemyRobot()
roborts_decision::EnemyRobot::SetEnemyMoveParameter
void SetEnemyMoveParameter()
Definition: enemy_robot.cpp:208
roborts_decision::EnemyRobot::SetIsSurvival
void SetIsSurvival(bool is_survival)
Definition: enemy_robot.cpp:73
roborts_decision::EnemyRobot::hp_
int hp_
Definition: enemy_robot.h:95
roborts_decision::EnemyRobot::EnemyRobot
EnemyRobot(const RobotId &robot_id, MyColor my_color)
Definition: enemy_robot.cpp:8
roborts_decision::EnemyRobot::enemy_pose_sub_
ros::Subscriber enemy_pose_sub_
Definition: enemy_robot.h:92
roborts_decision::EnemyRobot::robot_type_
RobotType robot_type_
Definition: enemy_robot.h:88
roborts_decision::EnemyRobot::kHeat
constexpr static double kHeat
Definition: enemy_robot.h:107
roborts_decision::EnemyRobot::SetIsDetected
void SetIsDetected(bool is_detected)
Definition: enemy_robot.cpp:109
roborts_decision::EnemyRobot::nh_
ros::NodeHandle nh_
Definition: enemy_robot.h:91
roborts_decision::Posture
Posture
Definition: blackboard_common.h:40
roborts_decision::EnemyRobot::getStanderdState
double getStanderdState() const
Definition: enemy_robot.cpp:123
roborts_decision::EnemyRobot::canMove
bool canMove() const
Definition: enemy_robot.cpp:163
roborts_decision::EnemyRobot
Definition: enemy_robot.h:16
roborts_decision::EnemyRobot::id_
RobotId id_
Definition: enemy_robot.h:87
roborts_decision::EnemyRobot::getHp
int getHp() const
Definition: enemy_robot.cpp:145
roborts_decision::EnemyRobot::SetPose
void SetPose(const ros::Time &stamp, const geometry_msgs::Point &position)
Definition: enemy_robot.cpp:82
roborts_decision::EnemyRobot::SetCurrentHeat
void SetCurrentHeat(const int heat)
Definition: enemy_robot.cpp:158
roborts_decision::EnemyRobot::pose_
geometry_msgs::PoseStamped pose_
Definition: enemy_robot.h:102
roborts_decision::EnemyRobot::getState
double getState() const
Definition: enemy_robot.cpp:114
roborts_decision::EnemyRobot::tNoShoot
double tNoShoot
Definition: enemy_robot.h:108
roborts_decision::RobotType
RobotType
Definition: blackboard_common.h:81