Decision Module  1.0
ICRA2020 AI Challenge Northwestern Polytechnical University Aoxiang Team Strategy Code
abstract_common_strategy.h
Go to the documentation of this file.
1 //
2 // Created by wpy on 2020/7/26.
3 //
4 
5 #ifndef ROBOTRTS_WS_ABSTRACT_COMMON_STRATEGY_H
6 #define ROBOTRTS_WS_ABSTRACT_COMMON_STRATEGY_H
7 
8 #include "../blackboard/my_robot.h"
9 #include "../blackboard/blackboard.h"
10 #include <typeinfo>
11 
12 namespace roborts_decision {
13 
17 enum class StrategyID{
18  stopMove,
25 
26  stopShoot,
29 };
30 
31 /*
32  * 普通策略的抽象类,其他策略都应继承
33  * 注意需要在子类定义构造函数
34  */
36 public:
37  AbstractCommonStrategy(std::shared_ptr<MyRobot> _p_my_robot_,
38  std::shared_ptr<Blackboard> _p_blackboard_)
39  : p_my_robot_(std::move(_p_my_robot_)),
40  p_blackboard_(std::move(_p_blackboard_)){
42  }
43 
44  virtual bool CanExecuteMe() = 0;
45 
46  virtual void run() = 0;
47 
48  virtual StrategyID getID() = 0;
49 
50  virtual BehaviorState Update() = 0;
51 
52  virtual void Reset() = 0;
53 
54  protected:
55  std::shared_ptr<MyRobot> p_my_robot_;
56  std::shared_ptr<Blackboard> p_blackboard_;
58 };
59 
60 }
61 #endif //ROBOTRTS_WS_ABSTRACT_COMMON_STRATEGY_H
roborts_decision::StrategyID::keepDirectionDefendMove
@ keepDirectionDefendMove
roborts_decision::AbstractCommonStrategy
Definition: abstract_common_strategy.h:35
roborts_decision::AbstractCommonStrategy::Reset
virtual void Reset()=0
roborts_decision::AbstractCommonStrategy::p_my_robot_
std::shared_ptr< MyRobot > p_my_robot_
Definition: abstract_common_strategy.h:55
roborts_decision::AbstractCommonStrategy::CanExecuteMe
virtual bool CanExecuteMe()=0
roborts_decision::BehaviorState::IDLE
@ IDLE
Idle state, state as default or after cancellation.
roborts_decision::StrategyID::keepDirectionAttackMove
@ keepDirectionAttackMove
roborts_decision::StrategyID
StrategyID
Definition: abstract_common_strategy.h:17
roborts_decision::StrategyID::captureEnemyBloodMove
@ captureEnemyBloodMove
roborts_decision::AbstractCommonStrategy::getID
virtual StrategyID getID()=0
roborts_decision::StrategyID::toBetterOppShoot
@ toBetterOppShoot
roborts_decision::StrategyID::stopShoot
@ stopShoot
roborts_decision::StrategyID::stopMove
@ stopMove
roborts_decision::AbstractCommonStrategy::p_blackboard_
std::shared_ptr< Blackboard > p_blackboard_
Definition: abstract_common_strategy.h:56
roborts_decision
Definition: behavior_test_node.h:14
roborts_decision::StrategyID::captureBulletsMove
@ captureBulletsMove
roborts_decision::AbstractCommonStrategy::Update
virtual BehaviorState Update()=0
roborts_decision::AbstractCommonStrategy::behavior_state_
BehaviorState behavior_state_
Definition: abstract_common_strategy.h:57
roborts_decision::StrategyID::exploreMove
@ exploreMove
roborts_decision::StrategyID::captureHomeBloodMove
@ captureHomeBloodMove
roborts_decision::BehaviorState
BehaviorState
Behavior state.
Definition: behavior_state.h:11
roborts_decision::AbstractCommonStrategy::AbstractCommonStrategy
AbstractCommonStrategy(std::shared_ptr< MyRobot > _p_my_robot_, std::shared_ptr< Blackboard > _p_blackboard_)
Definition: abstract_common_strategy.h:37
roborts_decision::AbstractCommonStrategy::run
virtual void run()=0
roborts_decision::StrategyID::toWorseOppShoot
@ toWorseOppShoot