#include <my_robot.h>
|
constexpr static double | kBlood = 0.9 |
|
constexpr static double | kBullet = 0.8 |
|
constexpr static double | kHeat = 0.1 |
|
◆ MyRobot()
MyRobot::MyRobot |
( |
RobotId |
id, |
|
|
const ros::NodeHandle & |
nh = ros::NodeHandle("~") |
|
) |
| |
|
explicit |
◆ ~MyRobot()
◆ 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()
◆ 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()
◆ getMyRobotPoint()
roborts_common::Point2D MyRobot::getMyRobotPoint |
( |
| ) |
const |
◆ getNextPoint()
const roborts_common::Point2D & MyRobot::getNextPoint |
( |
| ) |
const |
◆ getPChassisExecutor()
◆ getPGimbalExecutor()
◆ getRemainingProjectiles()
int MyRobot::getRemainingProjectiles |
( |
| ) |
const |
◆ getRobotType()
◆ 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()
◆ 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]
◆ 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()
◆ UpdateChassisOdomPose()
void MyRobot::UpdateChassisOdomPose |
( |
| ) |
|
|
private |
◆ UpdateGimbalMapPose()
void MyRobot::UpdateGimbalMapPose |
( |
| ) |
|
|
private |
◆ UpdateGimbalOdomPose()
void MyRobot::UpdateGimbalOdomPose |
( |
| ) |
|
|
private |
◆ 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_
◆ 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_
◆ 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:
- src/ICRA-Firefly-RoboRTS/roborts_decision/blackboard/my_robot.h
- src/ICRA-Firefly-RoboRTS/roborts_decision/blackboard/my_robot.cpp