#include <strategy_execute.h>
The class executes strategy selected by dqn_network. It implements the single instance mode, the instance can be obtained by StrategyExecute::GetStrategyExecute()
◆ StrategyExecute()
StrategyExecute::StrategyExecute |
( |
const ros::NodeHandle & |
nh = ros::NodeHandle("~") | ) |
|
|
explicit |
◆ ~StrategyExecute()
roborts_decision::StrategyExecute::~StrategyExecute |
( |
| ) |
|
|
default |
◆ ChooseStrategyToExceed()
void StrategyExecute::ChooseStrategyToExceed |
( |
const std::shared_ptr< MyRobot > & |
p_my_robot, |
|
|
int |
data |
|
) |
| |
Convert the strategy id to specific strategy.
◆ GetStrategyExecute()
◆ 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
-
msg | the specific type of msg |
◆ 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: