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

#include <my_robot.h>

Public Member Functions

 MyRobot (RobotId id, const ros::NodeHandle &nh=ros::NodeHandle("~"))
 
virtual ~MyRobot ()
 
bool operator== (const MyRobot &rhs) const
 
bool operator!= (const MyRobot &rhs) const
 
void update ()
 
RobotId GetId () const
 
RobotType getRobotType () const
 
void setRobotType (RobotType robot_type)
 
std::string robotTypeToString (const RobotType robot_type)
 
int getHp () const
 
int getCurrentHeat () const
 
int getRemainingProjectiles () const
 
bool isSurvival () const
 
void setIsSurvival (bool is_survival)
 
bool isNoMove () const
 
bool isNoShoot () const
 
bool isShot () const
 
const std::vector< ArmorId > & getArmorsUnderAttack () const
 
const roborts_msgs::ArmorsDetected & getArmorsInEyes () const
 
const geometry_msgs::PoseStamped & getChassisMapPose () const
 
uint32_t getStatusCode ()
 
const geometry_msgs::PoseStamped & getChassisOdomPose ()
 
const geometry_msgs::PoseStamped & getGimbalMapPose ()
 
const geometry_msgs::PoseStamped & getGimbalOdomPose ()
 
roborts_common::Point2D getMyRobotPoint () const
 
MyRobotBehavior getCurrentBehavior () const
 
void setCurrentBehavior (MyRobotBehavior current_behavior)
 
double getEffectiveShootDistance () const
 
double getState () const
 
const roborts_common::Point2D & getNextPoint () const
 
void setNextPoint (const roborts_common::Point2D &nextPoint)
 
Signal getSignal () const
 
void spinForword (const double &tarX, const double &tarY)
 
void spinInPlace (const double &angularVelocity)
 
void stayStill ()
 
void keepDirectionMove (double tar_x, double tar_y, double direction)
 
double getSafeDirection (const geometry_msgs::PoseStamped &pose_enemy)
 
void avoidanceMove (double x, double y)
 
double GetArmorTowards (ArmorId armor_id)
 
bool shoot (double speed, int number=data::MAX)
 
int shootBulletsMaxNumber (double speed) const
 
double TowardWPosShoot (double tar_x, double tar_y, double tar_z)
 
int GetShootEnemyId ()
 
void SetShootEnemyId (const int id)
 
int GetShootNulletsNumber ()
 
void SetShootNulletsNumber (const int num_bullets)
 
void SetHomeShootParameter ()
 
void SetHomeMoveParameter ()
 

Private Member Functions

std::shared_ptr< ChassisExecutorgetPChassisExecutor ()
 
std::shared_ptr< GimbalExecutorgetPGimbalExecutor ()
 
void setGimbalOdomPose (const double &gimbal_goal_map_pitch, const double &gimbal_goal_map_yaw)
 
roborts_msgs::GimbalAngle shootAimed (geometry_msgs::Point32 &target)
 
void shoot ()
 
void setSignal (Signal signal)
 
double changeFrictionWheelSpeedToShootSpeed (double frictionWhellSpeed)
 
void ArmorsUnderAttackCallback (const roborts_msgs::RobotDamage::ConstPtr &msg)
 
void HeatCallback (const roborts_msgs::RobotHeat::ConstPtr &msg)
 
void RobotStatusCallback (const roborts_msgs::RobotStatus::ConstPtr &msg)
 
void ArmorsInEyesCallback (const roborts_msgs::ArmorsDetected::ConstPtr &msg)
 
void RemainingProjectilesCallback (const roborts_msgs::ShootInfo::ConstPtr &msg)
 
void ChassisMapPoseCallback (const geometry_msgs::PoseStamped::ConstPtr &msg)
 
void UpdateChassisOdomPose ()
 
void UpdateGimbalMapPose ()
 
void UpdateGimbalOdomPose ()
 

Private Attributes

ros::NodeHandle nh_
 
ros::Subscriber remaining_projectiles_sub_
 
ros::Subscriber armors_under_attack_sub_
 
ros::Subscriber heat_sub_
 
ros::Subscriber armors_in_eyes_sub_
 
ros::Subscriber robot_status_sub_
 
ros::Subscriber robot_map_pose_sub_
 
std::shared_ptr< tf::TransformListener > tf_ptr_
 
std::shared_ptr< std::thread > tf_thread_ptr_
 
std::shared_ptr< std::thread > p_ros_spin_thread_
 
RobotId id_
 
RobotType robot_type_
 
int remaining_hp_
 
int max_hp_
 
int current_heat_
 
bool no_move_
 
bool no_shoot_
 
double tNoShoot = 0
 
double tNoMove = 0
 
int remaining_projectiles_
 
bool is_survival_
 
int shoot_enemy_id_
 
int shoot_bullets_this_time_
 
std::vector< ArmorIdarmors_under_attack_
 
roborts_msgs::ArmorsDetected armors_in_eyes_
 
geometry_msgs::PoseStamped chassis_map_pose_
 
geometry_msgs::PoseStamped chassis_odom_pose_
 
geometry_msgs::PoseStamped gimbal_map_pose_
 
geometry_msgs::PoseStamped gimbal_odom_pose_
 
MyRobotBehavior current_behavior_
 
std::shared_ptr< ChassisExecutorp_chassis_executor_
 
std::shared_ptr< GimbalExecutorp_gimbal_executor_
 
ros::Publisher shoot_pub_
 
roborts_common::Point2D nextPoint_
 
roborts_decision::Signal signal_
 

Static Private Attributes

constexpr static double kBlood = 0.9
 
constexpr static double kBullet = 0.8
 
constexpr static double kHeat = 0.1
 

Constructor & Destructor Documentation

◆ MyRobot()

MyRobot::MyRobot ( RobotId  id,
const ros::NodeHandle &  nh = ros::NodeHandle("~") 
)
explicit

◆ ~MyRobot()

MyRobot::~MyRobot ( )
virtualdefault

Member Function Documentation

◆ ArmorsInEyesCallback()

void MyRobot::ArmorsInEyesCallback ( const roborts_msgs::ArmorsDetected::ConstPtr &  msg)
private

◆ ArmorsUnderAttackCallback()

void MyRobot::ArmorsUnderAttackCallback ( const roborts_msgs::RobotDamage::ConstPtr &  msg)
private

◆ avoidanceMove()

void MyRobot::avoidanceMove ( double  x,
double  y 
)

◆ changeFrictionWheelSpeedToShootSpeed()

double MyRobot::changeFrictionWheelSpeedToShootSpeed ( double  frictionWhellSpeed)
private

◆ ChassisMapPoseCallback()

void MyRobot::ChassisMapPoseCallback ( const geometry_msgs::PoseStamped::ConstPtr &  msg)
private

◆ getArmorsInEyes()

const roborts_msgs::ArmorsDetected & MyRobot::getArmorsInEyes ( ) const

◆ getArmorsUnderAttack()

const std::vector< ArmorId > & MyRobot::getArmorsUnderAttack ( ) const

暂定使用方法为如果有被攻击的装甲板,size不为0,并且返回ArmorId

Returns

◆ GetArmorTowards()

double MyRobot::GetArmorTowards ( ArmorId  armor_id)

◆ getChassisMapPose()

const geometry_msgs::PoseStamped & MyRobot::getChassisMapPose ( ) const

◆ getChassisOdomPose()

const geometry_msgs::PoseStamped & MyRobot::getChassisOdomPose ( )

◆ getCurrentBehavior()

MyRobotBehavior MyRobot::getCurrentBehavior ( ) const

◆ getCurrentHeat()

int MyRobot::getCurrentHeat ( ) const

◆ getEffectiveShootDistance()

double MyRobot::getEffectiveShootDistance ( ) const

◆ getGimbalMapPose()

const geometry_msgs::PoseStamped & MyRobot::getGimbalMapPose ( )

◆ getGimbalOdomPose()

const geometry_msgs::PoseStamped & MyRobot::getGimbalOdomPose ( )

◆ getHp()

int MyRobot::getHp ( ) const

◆ GetId()

RobotId MyRobot::GetId ( ) const

◆ getMyRobotPoint()

roborts_common::Point2D MyRobot::getMyRobotPoint ( ) const

◆ getNextPoint()

const roborts_common::Point2D & MyRobot::getNextPoint ( ) const

◆ getPChassisExecutor()

std::shared_ptr< ChassisExecutor > MyRobot::getPChassisExecutor ( )
private

◆ getPGimbalExecutor()

std::shared_ptr< GimbalExecutor > MyRobot::getPGimbalExecutor ( )
private

◆ getRemainingProjectiles()

int MyRobot::getRemainingProjectiles ( ) const

◆ getRobotType()

RobotType MyRobot::getRobotType ( ) const

◆ getSafeDirection()

double MyRobot::getSafeDirection ( const geometry_msgs::PoseStamped &  pose_enemy)

◆ GetShootEnemyId()

int MyRobot::GetShootEnemyId ( )

◆ GetShootNulletsNumber()

int MyRobot::GetShootNulletsNumber ( )

◆ getSignal()

Signal MyRobot::getSignal ( ) const

◆ getState()

double roborts_decision::MyRobot::getState ( ) const

◆ getStatusCode()

uint32_t MyRobot::getStatusCode ( )

◆ HeatCallback()

void MyRobot::HeatCallback ( const roborts_msgs::RobotHeat::ConstPtr &  msg)
private

◆ isNoMove()

bool MyRobot::isNoMove ( ) const

◆ isNoShoot()

bool MyRobot::isNoShoot ( ) const

◆ isShot()

bool MyRobot::isShot ( ) const

TODO 返回我方机器人是否被攻击

Returns

◆ isSurvival()

bool MyRobot::isSurvival ( ) const

◆ keepDirectionMove()

void MyRobot::keepDirectionMove ( double  tar_x,
double  tar_y,
double  direction 
)

实现机器人以某个朝向移动

Parameters
tar_x目标点x坐标
tar_y目标点y坐标
direction到达点位点目标方向

◆ operator!=()

bool MyRobot::operator!= ( const MyRobot rhs) const

◆ operator==()

bool MyRobot::operator== ( const MyRobot rhs) const

◆ RemainingProjectilesCallback()

void MyRobot::RemainingProjectilesCallback ( const roborts_msgs::ShootInfo::ConstPtr &  msg)
private

◆ RobotStatusCallback()

void MyRobot::RobotStatusCallback ( const roborts_msgs::RobotStatus::ConstPtr &  msg)
private

◆ robotTypeToString()

std::string MyRobot::robotTypeToString ( const RobotType  robot_type)

◆ setCurrentBehavior()

void MyRobot::setCurrentBehavior ( MyRobotBehavior  current_behavior)

◆ setGimbalOdomPose()

void MyRobot::setGimbalOdomPose ( const double &  gimbal_goal_map_pitch,
const double &  gimbal_goal_map_yaw 
)
private

◆ SetHomeMoveParameter()

void roborts_decision::MyRobot::SetHomeMoveParameter ( )

◆ SetHomeShootParameter()

void roborts_decision::MyRobot::SetHomeShootParameter ( )

◆ setIsSurvival()

void MyRobot::setIsSurvival ( bool  is_survival)

◆ setNextPoint()

void MyRobot::setNextPoint ( const roborts_common::Point2D &  nextPoint)

◆ setRobotType()

void MyRobot::setRobotType ( RobotType  robot_type)

◆ SetShootEnemyId()

void MyRobot::SetShootEnemyId ( const int  id)

◆ SetShootNulletsNumber()

void MyRobot::SetShootNulletsNumber ( const int  num_bullets)

◆ setSignal()

void MyRobot::setSignal ( Signal  signal)
private

◆ shoot() [1/2]

void MyRobot::shoot ( )
private

◆ shoot() [2/2]

bool MyRobot::shoot ( double  speed,
int  number = data::MAX 
)

◆ shootAimed()

roborts_msgs::GimbalAngle MyRobot::shootAimed ( geometry_msgs::Point32 &  target)
private

◆ shootBulletsMaxNumber()

int MyRobot::shootBulletsMaxNumber ( double  speed) const

◆ spinForword()

void MyRobot::spinForword ( const double &  tarX,
const double &  tarY 
)

◆ spinInPlace()

void MyRobot::spinInPlace ( const double &  angularVelocity)

◆ stayStill()

void MyRobot::stayStill ( )

◆ TowardWPosShoot()

double MyRobot::TowardWPosShoot ( double  tar_x,
double  tar_y,
double  tar_z 
)

◆ update()

void MyRobot::update ( )

◆ UpdateChassisOdomPose()

void MyRobot::UpdateChassisOdomPose ( )
private

◆ UpdateGimbalMapPose()

void MyRobot::UpdateGimbalMapPose ( )
private

◆ UpdateGimbalOdomPose()

void MyRobot::UpdateGimbalOdomPose ( )
private

Member Data Documentation

◆ armors_in_eyes_

roborts_msgs::ArmorsDetected roborts_decision::MyRobot::armors_in_eyes_
private

◆ armors_in_eyes_sub_

ros::Subscriber roborts_decision::MyRobot::armors_in_eyes_sub_
private

◆ armors_under_attack_

std::vector<ArmorId> roborts_decision::MyRobot::armors_under_attack_
private

◆ armors_under_attack_sub_

ros::Subscriber roborts_decision::MyRobot::armors_under_attack_sub_
private

◆ chassis_map_pose_

geometry_msgs::PoseStamped roborts_decision::MyRobot::chassis_map_pose_
private

◆ chassis_odom_pose_

geometry_msgs::PoseStamped roborts_decision::MyRobot::chassis_odom_pose_
private

◆ current_behavior_

MyRobotBehavior roborts_decision::MyRobot::current_behavior_
private

◆ current_heat_

int roborts_decision::MyRobot::current_heat_
private

◆ gimbal_map_pose_

geometry_msgs::PoseStamped roborts_decision::MyRobot::gimbal_map_pose_
private

◆ gimbal_odom_pose_

geometry_msgs::PoseStamped roborts_decision::MyRobot::gimbal_odom_pose_
private

◆ heat_sub_

ros::Subscriber roborts_decision::MyRobot::heat_sub_
private

◆ id_

RobotId roborts_decision::MyRobot::id_
private

◆ is_survival_

bool roborts_decision::MyRobot::is_survival_
private

◆ kBlood

constexpr static double roborts_decision::MyRobot::kBlood = 0.9
staticconstexprprivate

◆ kBullet

constexpr static double roborts_decision::MyRobot::kBullet = 0.8
staticconstexprprivate

◆ kHeat

constexpr static double roborts_decision::MyRobot::kHeat = 0.1
staticconstexprprivate

◆ max_hp_

int roborts_decision::MyRobot::max_hp_
private

◆ nextPoint_

roborts_common::Point2D roborts_decision::MyRobot::nextPoint_
private

◆ nh_

ros::NodeHandle roborts_decision::MyRobot::nh_
private

◆ no_move_

bool roborts_decision::MyRobot::no_move_
private

◆ no_shoot_

bool roborts_decision::MyRobot::no_shoot_
private

◆ p_chassis_executor_

std::shared_ptr<ChassisExecutor> roborts_decision::MyRobot::p_chassis_executor_
private

◆ p_gimbal_executor_

std::shared_ptr<GimbalExecutor> roborts_decision::MyRobot::p_gimbal_executor_
private

◆ p_ros_spin_thread_

std::shared_ptr<std::thread> roborts_decision::MyRobot::p_ros_spin_thread_
private

◆ remaining_hp_

int roborts_decision::MyRobot::remaining_hp_
private

◆ remaining_projectiles_

int roborts_decision::MyRobot::remaining_projectiles_
private

◆ remaining_projectiles_sub_

ros::Subscriber roborts_decision::MyRobot::remaining_projectiles_sub_
private

◆ robot_map_pose_sub_

ros::Subscriber roborts_decision::MyRobot::robot_map_pose_sub_
private

◆ robot_status_sub_

ros::Subscriber roborts_decision::MyRobot::robot_status_sub_
private

◆ robot_type_

RobotType roborts_decision::MyRobot::robot_type_
private

◆ shoot_bullets_this_time_

int roborts_decision::MyRobot::shoot_bullets_this_time_
private

◆ shoot_enemy_id_

int roborts_decision::MyRobot::shoot_enemy_id_
private

◆ shoot_pub_

ros::Publisher roborts_decision::MyRobot::shoot_pub_
private

◆ signal_

roborts_decision::Signal roborts_decision::MyRobot::signal_
private

◆ tf_ptr_

std::shared_ptr<tf::TransformListener> roborts_decision::MyRobot::tf_ptr_
private

◆ tf_thread_ptr_

std::shared_ptr<std::thread> roborts_decision::MyRobot::tf_thread_ptr_
private

◆ tNoMove

double roborts_decision::MyRobot::tNoMove = 0
private

◆ tNoShoot

double roborts_decision::MyRobot::tNoShoot = 0
private

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