Decision Module  1.0
ICRA2020 AI Challenge Northwestern Polytechnical University Aoxiang Team Strategy Code
strategy_execute.h
Go to the documentation of this file.
1 //
2 // Created by wpy on 2020/8/15.
3 //
4 
5 #ifndef ROBOTRTS_WS_SRC_ICRA_FIREFLY_ROBORTS_ROBORTS_DECISION_STRATEGY_STRATEGY_EXECUTE_H_
6 #define ROBOTRTS_WS_SRC_ICRA_FIREFLY_ROBORTS_ROBORTS_DECISION_STRATEGY_STRATEGY_EXECUTE_H_
7 
18 namespace roborts_decision {
19 
20 
26  public:
28  explicit StrategyExecute(const ros::NodeHandle &nh = ros::NodeHandle("~"));
29  ~StrategyExecute() = default;
30 
31  static std::shared_ptr<StrategyExecute> GetStrategyExecute();
32 
34  void ChooseStrategyToExceed(const std::shared_ptr<MyRobot> &p_my_robot, int data);
35 
36  private:
37  std::shared_ptr<Blackboard> p_blackboard_;
38 
39  ros::NodeHandle nh_;
40  ros::Subscriber next_decision_sub_;
41 
42  static std::shared_ptr<StrategyExecute> p_strategy_execute_;
43 
46  void NextDecisionCallBack(const std_msgs::Int32::ConstPtr &msg);
47 
48 
49 };
50 }
51 #endif //ROBOTRTS_WS_SRC_ICRA_FIREFLY_ROBORTS_ROBORTS_DECISION_STRATEGY_STRATEGY_EXECUTE_H_
roborts_decision::StrategyExecute::p_blackboard_
std::shared_ptr< Blackboard > p_blackboard_
Definition: strategy_execute.h:37
toWorseOpp_shoot_strategy.h
roborts_decision::StrategyExecute::StrategyExecute
StrategyExecute(const ros::NodeHandle &nh=ros::NodeHandle("~"))
the constructor
Definition: strategy_execute.cpp:11
keepDirection_attack_move_strategy.h
keepDirection_defense_move_strategy.h
roborts_decision::StrategyExecute::GetStrategyExecute
static std::shared_ptr< StrategyExecute > GetStrategyExecute()
Definition: strategy_execute.cpp:117
roborts_decision::StrategyExecute::ChooseStrategyToExceed
void ChooseStrategyToExceed(const std::shared_ptr< MyRobot > &p_my_robot, int data)
Convert the strategy id to specific strategy.
Definition: strategy_execute.cpp:20
stop_move_strategy.h
captureEnemyBlood_move_strategy.h
roborts_decision::StrategyExecute::~StrategyExecute
~StrategyExecute()=default
roborts_decision::StrategyExecute::next_decision_sub_
ros::Subscriber next_decision_sub_
Definition: strategy_execute.h:40
roborts_decision::StrategyExecute::p_strategy_execute_
static std::shared_ptr< StrategyExecute > p_strategy_execute_
Definition: strategy_execute.h:42
roborts_decision
Definition: behavior_test_node.h:14
roborts_decision::data
Definition: blackboard_common.h:13
abstract_common_strategy.h
roborts_decision::StrategyExecute::NextDecisionCallBack
void NextDecisionCallBack(const std_msgs::Int32::ConstPtr &msg)
Definition: strategy_execute.cpp:99
captureHomeBlood_move_strategy.h
roborts_decision::StrategyExecute
Definition: strategy_execute.h:25
roborts_decision::StrategyExecute::nh_
ros::NodeHandle nh_
Definition: strategy_execute.h:39
captureBullets_move_strategy.h
stop_shoot_strategy.h
toBetterOpp_shoot_strategy.h