Skip to content
This repository has been archived by the owner on Jan 23, 2024. It is now read-only.

Use ros sports game state msg #344

Draft
wants to merge 2 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@

Provides information about the current game state.
"""
from bitbots_msgs.msg import GameState
from bitbots_utils.utils import get_parameters_from_other_node
from game_controller_hl_interfaces.msg import GameState
from rclpy.node import Node


Expand Down
1 change: 1 addition & 0 deletions bitbots_blackboard/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
<depend>tf_transformations</depend>
<exec_depend>bio_ik_msgs</exec_depend>
<exec_depend>bitbots_msgs</exec_depend>
<exec_depend>game_controller_hl_interfaces</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>soccer_vision_3d_msgs</exec_depend>
Expand Down
3 changes: 2 additions & 1 deletion bitbots_body_behavior/bitbots_body_behavior/body_behavior.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,10 @@
import rclpy
import tf2_ros as tf2
from ament_index_python import get_package_share_directory
from bitbots_msgs.msg import GameState, RobotControlState, TeamData
from bitbots_msgs.msg import RobotControlState, TeamData
from bitbots_tf_listener import TransformListener
from dynamic_stack_decider.dsd import DSD
from game_controller_hl_interfaces.msg import GameState
from geometry_msgs.msg import PoseWithCovarianceStamped, Twist, TwistWithCovarianceStamped
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup
from rclpy.duration import Duration
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
from bitbots_msgs.msg import GameState
from dynamic_stack_decider.abstract_decision_element import AbstractDecisionElement
from game_controller_hl_interfaces.msg import GameState

from bitbots_blackboard.blackboard import BodyBlackboard

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,15 +10,15 @@ def __init__(self, blackboard, dsd, parameters=None):
super().__init__(blackboard, dsd, parameters)

def perform(self, reevaluate=False):
# Get nessesary data
red_cards = self.blackboard.gamestate.get_red_cards()
own_id = self.blackboard.misc.bot_id

# iterate through all red card states except the own one
for i in range(len(red_cards)):
if i != own_id:
if not red_cards[i]:
return "NO"
return "YES"

# Use generator comprehension to check if all red cards are true except our own
if all(x for i, x in enumerate(red_cards) if i != own_id):
return "YES"
else:
return "NO"

def get_reevaluate(self):
return True
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
from bitbots_msgs.msg import GameState
from dynamic_stack_decider.abstract_decision_element import AbstractDecisionElement
from game_controller_hl_interfaces.msg import GameState

from bitbots_blackboard.blackboard import BodyBlackboard

Expand Down
2 changes: 1 addition & 1 deletion bitbots_body_behavior/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
<depend>bitbots_msgs</depend>
<depend>bitbots_utils</depend>
<depend>dynamic_stack_decider</depend>
<depend>game_controller_hl_interfaces</depend>
<depend>geometry_msgs</depend>
<depend>python3-numpy</depend>
<depend>rclpy</depend>
Expand All @@ -27,7 +28,6 @@
<depend>tf_transformations</depend>
<depend>tf2</depend>


<export>
<rosdoc config="rosdoc.yaml"/>
<bitbots_documentation>
Expand Down
Loading