Skip to content

Commit

Permalink
Use ros sports game controller client (#326)
Browse files Browse the repository at this point in the history
  • Loading branch information
Flova authored Jan 24, 2024
2 parents aa149aa + cd652d8 commit 9e5c0ed
Show file tree
Hide file tree
Showing 42 changed files with 48 additions and 876 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,7 @@ def cost_at_relative_xy(self, x: float, y: float) -> float:
# Transform point of interest to the map
point = self._blackboard.tf_buffer.transform(point, self.map_frame, timeout=Duration(seconds=0.3))
except (tf2.ConnectivityException, tf2.LookupException, tf2.ExtrapolationException) as e:
self._blackboard.node.get_logger().warn(e)
self._blackboard.node.get_logger().warn(str(e))
return 0.0

return self.get_cost_at_field_position(point.point.x, point.point.y)
Expand Down Expand Up @@ -338,7 +338,7 @@ def get_cost_of_kick_relative(self, x: float, y: float, direction: float, kick_l
pose = self._blackboard.tf_buffer.transform(pose, self.map_frame, timeout=Duration(seconds=0.3))

except (tf2.ConnectivityException, tf2.LookupException, tf2.ExtrapolationException) as e:
self._blackboard.node.get_logger().warn(e)
self._blackboard.node.get_logger().warn(str(e))
return 0.0
d = euler_from_quaternion(numpify(pose.pose.orientation))[2]
return self.get_cost_of_kick(pose.pose.position.x, pose.pose.position.y, d, kick_length, angular_range)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,10 +5,9 @@
Provides information about the current game state.
"""
from bitbots_utils.utils import get_parameters_from_other_node
from game_controller_hl_interfaces.msg import GameState
from rclpy.node import Node

from bitbots_msgs.msg import GameState


class GameStatusCapsule:
def __init__(self, node: Node):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -175,7 +175,7 @@ def get_ball_position_uv(self) -> Tuple[float, float]:
ball, self.base_footprint_frame, timeout=Duration(seconds=0.2)
).point
except tf2.ExtrapolationException as e:
self._blackboard.node.get_logger().warn(e)
self._blackboard.node.get_logger().warn(str(e))
self._blackboard.node.get_logger().error("Severe transformation problem concerning the ball!")
return None
return ball_bfp.x, ball_bfp.y
Expand Down
2 changes: 2 additions & 0 deletions bitbots_behavior/bitbots_blackboard/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -22,8 +22,10 @@
<build_depend>bitbots_docs</build_depend>
<depend>bitbots_tf_listener</depend>
<depend>bitbots_utils</depend>
<depend>game_controller_hl_interfaces</depend>
<depend>python3-numpy</depend>
<depend>rclpy</depend>
<depend>ros2_numpy</depend>
<depend>tf_transformations</depend>
<exec_depend>bio_ik_msgs</exec_depend>
<exec_depend>bitbots_msgs</exec_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,14 +16,15 @@
from bitbots_blackboard.blackboard import BodyBlackboard
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
from rclpy.executors import MultiThreadedExecutor
from rclpy.node import Node
from soccer_vision_3d_msgs.msg import RobotArray

from bitbots_msgs.msg import GameState, RobotControlState, TeamData
from bitbots_msgs.msg import RobotControlState, TeamData


class BodyDSD:
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
from bitbots_blackboard.blackboard import BodyBlackboard
from dynamic_stack_decider.abstract_decision_element import AbstractDecisionElement

from bitbots_msgs.msg import GameState
from game_controller_hl_interfaces.msg import GameState


class GameStateDecider(AbstractDecisionElement):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,15 +9,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,7 +1,6 @@
from bitbots_blackboard.blackboard import BodyBlackboard
from dynamic_stack_decider.abstract_decision_element import AbstractDecisionElement

from bitbots_msgs.msg import GameState
from game_controller_hl_interfaces.msg import GameState


class SecondaryStateDecider(AbstractDecisionElement):
Expand Down
1 change: 1 addition & 0 deletions bitbots_behavior/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 Down
6 changes: 5 additions & 1 deletion bitbots_misc/bitbots_bringup/launch/highlevel.launch
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,12 @@

<!-- launch game controller -->
<group if="$(var game_controller)">
<include file="$(find-pkg-share humanoid_league_game_controller)/launch/game_controller.launch">
<include file="$(find-pkg-share game_controller_hl)/launch/game_controller.launch">
<arg name="sim" value="$(var sim)" />
<arg name="use_parameter_blackboard" value="true" />
<arg name="parameter_blackboard_name" value="parameter_blackboard" />
<arg name="team_id_param_name" value="team_id" />
<arg name="bot_id_param_name" value="bot_id" />
</include>
</group>

Expand Down
1 change: 1 addition & 0 deletions bitbots_misc/bitbots_bringup/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
<exec_depend>bitbots_ros_control</exec_depend>
<exec_depend>bitbots_utils</exec_depend>
<exec_depend>bitbots_vision</exec_depend>
<exec_depend>game_controller_hl</exec_depend>
<exec_depend>humanoid_base_footprint</exec_depend>
<exec_depend>soccer_ipm</exec_depend>
<exec_depend>system_monitor</exec_depend>
Expand Down
2 changes: 1 addition & 1 deletion bitbots_misc/bitbots_docs/docs/manual/testing/sim_test.rst
Original file line number Diff line number Diff line change
Expand Up @@ -37,4 +37,4 @@ Test the complete software stack in simulation
.. code-block:: bash
ros2 launch bitbots_bringup simulator_teamplayer.launch
ros2 run humanoid_league_game_controller sim_gamestate.py
ros2 run game_controller_hl sim_gamestate.py
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ In the simulator we should see a field with a single robot.

With ``game_controller:=false`` we ensure, that the game_controller_listener is not started as well, but instead
we will simulate the current gamestate by our own script (in another terminal):
``rr humanoid_league_game_controller sim_gamestate.py``
``rr game_controller_hl sim_gamestate.py``

Which allows us to simulate the current gamestate and different phases of the game.
Now everything is ready for some simulation testing.
Expand Down
1 change: 0 additions & 1 deletion bitbots_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,6 @@ rosidl_generate_interfaces(
"msg/Cpu.msg"
"msg/Filesystem.msg"
"msg/FootPressure.msg"
"msg/GameState.msg"
"msg/HeadMode.msg"
"msg/JointCommand.msg"
"msg/JointTorque.msg"
Expand Down
67 changes: 0 additions & 67 deletions bitbots_msgs/msg/GameState.msg

This file was deleted.

Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
from game_controller_hl_interfaces.msg import GameState

from bitbots_localization_handler.localization_dsd.decisions import AbstractLocalizationDecisionElement
from bitbots_msgs.msg import GameState


class CheckGameStateReceived(AbstractLocalizationDecisionElement):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,13 +4,14 @@
import rclpy
from ament_index_python import get_package_share_directory
from dynamic_stack_decider.dsd import DSD
from game_controller_hl_interfaces.msg import GameState
from geometry_msgs.msg import PoseWithCovarianceStamped
from rclpy.callback_groups import MutuallyExclusiveCallbackGroup, ReentrantCallbackGroup
from rclpy.executors import MultiThreadedExecutor
from rclpy.node import Node

from bitbots_localization_handler.localization_dsd.localization_blackboard import LocalizationBlackboard
from bitbots_msgs.msg import GameState, RobotControlState
from bitbots_msgs.msg import RobotControlState


def init(node: Node):
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,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 Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,11 +5,12 @@

import numpy as np
import rclpy
from game_controller_hl_interfaces.msg import GameState
from rclpy.node import Node
from sensor_msgs.msg import Image
from soccer_vision_2d_msgs.msg import BallArray, GoalpostArray, Robot, RobotArray

from bitbots_msgs.msg import Audio, GameState
from bitbots_msgs.msg import Audio
from bitbots_vision.vision_modules import candidate, debug, ros_utils

from . import detectors, object_manager, yoeo_handlers
Expand Down
1 change: 1 addition & 0 deletions bitbots_vision/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@
<exec_depend>rosidl_default_runtime</exec_depend>
<depend>bitbots_msgs</depend>
<depend>bitbots_utils</depend>
<depend>game_controller_hl_interfaces</depend>
<depend>geometry_msgs</depend>
<depend>image_transport</depend>
<depend>python3-numpy</depend>
Expand Down

This file was deleted.

11 changes: 0 additions & 11 deletions humanoid_league_misc/humanoid_league_game_controller/README.md

This file was deleted.

This file was deleted.

Binary file not shown.
Loading

0 comments on commit 9e5c0ed

Please sign in to comment.