Decision Module  1.0
ICRA2020 AI Challenge Northwestern Polytechnical University Aoxiang Team Strategy Code
roborts_decision::StrategyExecute Class Reference

#include <strategy_execute.h>

Public Member Functions

 StrategyExecute (const ros::NodeHandle &nh=ros::NodeHandle("~"))
 the constructor More...
 
 ~StrategyExecute ()=default
 
void ChooseStrategyToExceed (const std::shared_ptr< MyRobot > &p_my_robot, int data)
 Convert the strategy id to specific strategy. More...
 

Static Public Member Functions

static std::shared_ptr< StrategyExecuteGetStrategyExecute ()
 

Private Member Functions

void NextDecisionCallBack (const std_msgs::Int32::ConstPtr &msg)
 

Private Attributes

std::shared_ptr< Blackboardp_blackboard_
 
ros::NodeHandle nh_
 
ros::Subscriber next_decision_sub_
 

Static Private Attributes

static std::shared_ptr< StrategyExecutep_strategy_execute_ = nullptr
 

Detailed Description

The class executes strategy selected by dqn_network. It implements the single instance mode, the instance can be obtained by StrategyExecute::GetStrategyExecute()

Constructor & Destructor Documentation

◆ StrategyExecute()

StrategyExecute::StrategyExecute ( const ros::NodeHandle &  nh = ros::NodeHandle("~"))
explicit

the constructor

◆ ~StrategyExecute()

roborts_decision::StrategyExecute::~StrategyExecute ( )
default

Member Function Documentation

◆ ChooseStrategyToExceed()

void StrategyExecute::ChooseStrategyToExceed ( const std::shared_ptr< MyRobot > &  p_my_robot,
int  data 
)

Convert the strategy id to specific strategy.

◆ GetStrategyExecute()

std::shared_ptr< StrategyExecute > StrategyExecute::GetStrategyExecute ( )
static

◆ NextDecisionCallBack()

void StrategyExecute::NextDecisionCallBack ( const std_msgs::Int32::ConstPtr &  msg)
private

The callback will be called on every policy choice message dqn_network sends.

Parameters
msgthe specific type of msg

Member Data Documentation

◆ next_decision_sub_

ros::Subscriber roborts_decision::StrategyExecute::next_decision_sub_
private

◆ nh_

ros::NodeHandle roborts_decision::StrategyExecute::nh_
private

◆ p_blackboard_

std::shared_ptr<Blackboard> roborts_decision::StrategyExecute::p_blackboard_
private

◆ p_strategy_execute_

std::shared_ptr< StrategyExecute > StrategyExecute::p_strategy_execute_ = nullptr
staticprivate

The documentation for this class was generated from the following files: