开发中,不考虑向前兼容性,仅供参考,请谨慎使用。文档可能不会及时更新以反映代码的最新变化。
基于 BehaviorTree.CPP 和 BehaviorTree.ROS2 的行为树框架与插件,用于 RoboMaster 2025 赛季哨兵机器人。
- Ubuntu 22.04
- ROS2 Humble
- BehaviorTree.CPP (Developed with release 4.6.2)
mkdir -p ~/ros_ws
cd ~/ros_wspip install vcstool2git clone https://github.com/SMBU-PolarBear-Robotics-Team/pb2025_sentry_behavior.git src/pb2025_sentry_behaviorvcs import --recursive src < src/pb2025_sentry_behavior/dependencies.reposrosdepc install -r --from-paths src --ignore-src --rosdistro $ROS_DISTRO -ycolcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=releaseros2 launch pb2025_sentry_behavior pb2025_sentry_behavior_launch.py本包通过 referee_topic_translator.py 节点与裁判系统通信,将 dji_referee_protocol 的消息类型转换为 pb_rm_interfaces 类型供行为树使用。
依赖:
- dji_referee_protocol - DJI 裁判系统通信协议包
输入话题 (来自 dji_referee_protocol):
/referee/common/game_status(dji_referee_protocol/msg/GameStatus)/referee/common/robot_hp(dji_referee_protocol/msg/RobotHP)/referee/common/field_event(dji_referee_protocol/msg/FieldEvent)/referee/common/robot_performance(dji_referee_protocol/msg/RobotPerformance)/referee/common/robot_heat(dji_referee_protocol/msg/RobotHeat)/referee/common/robot_position(dji_referee_protocol/msg/RobotPosition)/referee/common/robot_buff(dji_referee_protocol/msg/RobotBuff)/referee/common/damage_state(dji_referee_protocol/msg/DamageState)/referee/common/allowed_shoot(dji_referee_protocol/msg/AllowedShoot)/referee/common/rfid_status(dji_referee_protocol/msg/RFIDStatus)/referee/common/ground_robot_position(dji_referee_protocol/msg/GroundRobotPosition)
输出话题 (供行为树使用):
referee/game_status(pb_rm_interfaces/msg/GameStatus)referee/all_robot_hp(pb_rm_interfaces/msg/GameRobotHP)referee/robot_status(pb_rm_interfaces/msg/RobotStatus)referee/rfid_status(pb_rm_interfaces/msg/RfidStatus)referee/event_data(pb_rm_interfaces/msg/EventData)referee/buff(pb_rm_interfaces/msg/Buff)referee/ground_robot_position(pb_rm_interfaces/msg/GroundRobotPosition)
CalculateAttackPose 动作节点用于计算并输出进攻坐标,该节点基于敌方坐标和全局代价地图生成候选点,过滤出可行点,并选择最佳攻击点。
Input Ports:
costmap_port:类型为nav_msgs::msg::OccupancyGrid,表示全局代价地图。tracker_port:类型为auto_aim_interfaces::msg::Target,表示视觉估计得到的目标状态信息。Related repo: armor_tracker
Output Ports:
goal:类型为geometry_msgs::msg::PoseStamped,表示发送给导航系统的目标姿态。
Parameters:
attack_radius:以目标位置为圆心的半径,default: 3.0。num_sectors:划分扇区数量,default: 36。cost_threshold:代价阈值,default: 50。robot_base_frame:机器人基坐标系,default: "chassis"。transform_tolerance:查询 tf 超时时间,default: 0.5。visualize:是否启用可视化,default: false。
- transformToCostmapFrame:将敌方位置转换到代价地图框架。
- generateCandidatePoints:生成候选攻击点。
- filterFeasiblePoints:过滤出可行的攻击点。
- selectBestPoint:选择最佳攻击点。
- createAttackPose:创建攻击姿态。
- createVisualizationMarkers:创建可视化标记。
以 geometry_msgs/msg/Twist 的形式发布速度,用于控制底盘运动。
创建 Client,以 nav2_msgs/action/NavigateToPose 的形式发送 Navigation2 目标点。
Caution
BehaviorTree.ROS2 中存在 bug,导致继承自 RosActionNode 的节点无法被正确 halt,最终导致行为树被 shutdown。因此,下面提供了一个以 topic 代替 action 发布 goal_pose 的临时方案 PubNav2Goal,坏处是无法实时获取到 action 的 feedback 和 result。
Related Issue: #18 Error when canceling action during halt()
以 geometry_msgs/msg/pose_stamped 的形式发布 Navigation2 目标点。
通过 GlobalBlackboard 获取实时的 pb_rm_interfaces::msg::RobotStatus 类型数据,判断机器人是否受到攻击,并根据裁判系统装甲模块反馈的信息输出敌方可能的角度位置。该条件节点会根据输入端口的配置,检查以下几个条件:
key_port:从 GlobalBlackboard 获取RobotStatus消息gimbal_pitch:输出固定的云台俯仰角度(0.0)gimbal_yaw:输出敌方可能的角度位置
如果检测到装甲板被击中,则返回 SUCCESS,并输出相应的云台角度;否则返回 FAILURE。
通过视觉模块判断是否感知到敌方。
armor_id:预期的装甲 ID 列表。可以是多个数字,用;分隔max_distance:敌方目标的最大距离
如果视觉模块感知到的敌方在 armor_id 列表中,且距离小于 max_distance,则返回 SUCCESS,否则返回 FAILURE。
通过 GlobalBlackboard 获取实时的 pb_rm_interfaces::msg::GameStatus 类型数据,判断当前比赛状态是否在输入的时间范围内且处于预期的比赛阶段。该条件节点会根据输入端口的配置,检查以下几个条件:
key_port:从 GlobalBlackboard 获取GameStatus消息expected_game_progress:预期的比赛阶段min_remain_time:最小剩余时间(秒)max_remain_time:最大剩余时间(秒)
如果比赛阶段和剩余时间都符合预期,则返回 SUCCESS,否则返回 FAILURE。
通过 GlobalBlackboard 获取实时的 pb_rm_interfaces::msg::RfidStatus 类型数据,判断机器人是否检测到指定的 RFID 标签。该条件节点会根据输入端口的配置,检查以下几个位置的 RFID 状态:
key_port:从 GlobalBlackboard 获取RfidStatus消息friendly_fortress_gain_point:己方堡垒增益点friendly_supply_zone_non_exchange:己方与兑换区不重叠的补给区 / RMUL 补给区friendly_supply_zone_exchange:己方与兑换区重叠的补给区center_gain_point:中心增益点(仅 RMUL 适用)
如果任意一个配置为 true 的位置检测到 RFID 标签,则返回 SUCCESS,否则返回 FAILURE。
通过 GlobalBlackboard 获取实时的 pb_rm_interfaces::msg::RobotStatus 类型数据,判断机器人的状态是否正常。该条件节点会根据输入端口的配置,检查以下几个条件:
key_port:从 GlobalBlackboard 获取RobotStatus消息hp_min:最低血量heat_max:最大发射机构的射击热量ammo_min:最小弹丸允许发弹量
如果机器人的 HP、热量和弹药量都在预期范围内,则返回 SUCCESS,否则返回 FAILURE。

