Skip to content

Commit 632cfe9

Browse files
committed
feat(behavior): descend with goalie on block/role-position
by creating a generalized cancelable `AbstractDynupAnimation` class, where each implementing class has to define a `reset_animation` method, which is triggered on pop. `GetWalkready` is also now using this as a base in our behavior. In the future this class should be merge with the similar `PlayAnimationDynup` class in HCM. We now descend as goalie both on our role position and when we are in the block position, which is handled by the `OnBlockPosition` decision.
1 parent bbc87f5 commit 632cfe9

File tree

7 files changed

+208
-86
lines changed

7 files changed

+208
-86
lines changed
Lines changed: 142 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,142 @@
1+
import time
2+
from abc import ABC, abstractmethod
3+
4+
import rclpy
5+
from bitbots_blackboard.body_blackboard import BodyBlackboard
6+
from dynamic_stack_decider.abstract_action_element import AbstractActionElement
7+
from rclpy.task import Future
8+
9+
from bitbots_msgs.action import Dynup
10+
11+
12+
# @TODO: merge/extract with hcm PlayAnimationDynup
13+
class AbstractDynupAnimation(AbstractActionElement, ABC):
14+
"""
15+
Dynup animation actions are blocking and do not pop themselves!
16+
This is because otherwise they would, reset themselves directly (e.g. after descend, ascend again)
17+
"""
18+
19+
blackboard: BodyBlackboard
20+
21+
def __init__(self, blackboard, dsd, parameters):
22+
super().__init__(blackboard, dsd, parameters)
23+
self.active = False
24+
self.first_perform = True
25+
self.dynup_action_current_goal: Future | None = None
26+
27+
def perform(self, reevaluate=False):
28+
if self.first_perform:
29+
# try to start animation
30+
success = self.start_animation()
31+
# if we fail, we need to abort this action
32+
if not success:
33+
self.blackboard.node.get_logger().error("Could not start animation. Will abort animation action!")
34+
self.pop()
35+
36+
self.first_perform = False
37+
38+
@abstractmethod
39+
def reset_animation(self):
40+
"""
41+
This method needs to reset the animation to its initial state.
42+
For example, if the animation is descend, the robot should stand up again.
43+
"""
44+
raise NotImplementedError
45+
46+
def start_animation(self) -> bool:
47+
"""
48+
This will NOT wait by itself. You have to check animation_finished() by yourself.
49+
50+
:return: True if the animation was started, False if not
51+
"""
52+
if not self.is_server_running():
53+
return False
54+
55+
# Dynup action server is running, we can start the walkready action
56+
self.send_animation_goal(self.direction)
57+
return True
58+
59+
def send_animation_goal(self, direction: str):
60+
goal = Dynup.Goal()
61+
goal.direction = direction
62+
self.active = True
63+
64+
self.dynup_action_current_goal = self.blackboard.animation.dynup_action_client.send_goal_async(goal)
65+
self.dynup_action_current_goal.add_done_callback(self.animation_finished_callback)
66+
67+
def is_server_running(self) -> bool:
68+
server_running = self.blackboard.animation.dynup_action_client.wait_for_server(timeout_sec=1)
69+
if not server_running:
70+
while not server_running and rclpy.ok():
71+
self.blackboard.node.get_logger().warn(
72+
"Dynup Action Server not running! Dynup cannot work without dynup server! "
73+
"Will now wait until server is accessible!",
74+
throttle_duration_sec=10.0,
75+
)
76+
server_running = self.blackboard.animation.dynup_action_client.wait_for_server(timeout_sec=1)
77+
if server_running:
78+
self.blackboard.node.get_logger().warn("Dynup server now running, 'DynupAnimation' action will go on.")
79+
else:
80+
self.blackboard.node.get_logger().warn("Dynup server did not start.")
81+
return False
82+
83+
return server_running
84+
85+
def stop_animation(self):
86+
if self.dynup_action_current_goal is not None:
87+
self.dynup_action_current_goal.result().cancel_goal_async()
88+
89+
def on_pop(self):
90+
"""
91+
Cancel the current goal when the action is popped
92+
"""
93+
super().on_pop()
94+
if not self.is_animation_finished():
95+
self.stop_animation()
96+
97+
self.set_inactive()
98+
self.reset_animation()
99+
100+
def animation_finished_callback(self, animation_done_future: Future):
101+
"""
102+
Dynup animation future callback, setting the action when the animation is finished
103+
"""
104+
animation_done_future.result().get_result_async().add_done_callback(lambda _: self.set_inactive())
105+
106+
def is_animation_finished(self) -> bool:
107+
return not self.active
108+
109+
def set_inactive(self):
110+
self.active = False
111+
112+
def set_active(self):
113+
self.active = True
114+
115+
116+
class Descend(AbstractDynupAnimation):
117+
def __init__(self, blackboard, dsd, parameters):
118+
super().__init__(blackboard, dsd, parameters)
119+
self.direction = Dynup.Goal.DIRECTION_DESCEND
120+
self.reset_direction = Dynup.Goal.DIRECTION_RISE
121+
122+
def reset_animation(self):
123+
self.set_active()
124+
self.send_animation_goal(self.reset_direction)
125+
126+
while not self.is_animation_finished():
127+
time.sleep(0.1)
128+
129+
130+
class GetWalkready(AbstractDynupAnimation):
131+
def __init__(self, blackboard, dsd, parameters):
132+
super().__init__(blackboard, dsd, parameters)
133+
self.direction = Dynup.Goal.DIRECTION_WALKREADY
134+
135+
def reset_animation(self):
136+
pass
137+
138+
def perform(self, reevaluate=False):
139+
super().perform(reevaluate)
140+
141+
if self.is_animation_finished():
142+
self.pop()

bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/get_walkready.py

Lines changed: 0 additions & 80 deletions
This file was deleted.

bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/actions/go_to_block_position.py

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,7 @@ class GoToBlockPosition(AbstractActionElement):
1212

1313
def __init__(self, blackboard, dsd, parameters):
1414
super().__init__(blackboard, dsd, parameters)
15+
self.blocking = parameters.get("blocking", True)
1516
self.block_position_goal_offset = self.blackboard.config["block_position_goal_offset"]
1617
self.block_radius = self.blackboard.config["block_radius_robot"]
1718
self.left_goalpost_position = [
@@ -64,13 +65,16 @@ def perform(self, reevaluate=False):
6465

6566
self.blackboard.pathfinding.publish(pose_msg)
6667

68+
if not self.blocking:
69+
self.pop()
70+
6771
def _calc_opening_angle(self, ball_to_line: float, ball_pos: tuple) -> float:
6872
"""
6973
Calculates the opening angle of the ball to both goalposts.
7074
With it we can get the angle bisector, in which we place the robot.
7175
Args:
7276
ball_to_line: distance of the ball to our goal line
73-
ball_pos: ball position in world koordinate system
77+
ball_pos: ball position in world coordinate system
7478
7579
Returns:
7680
float: opening angle
Lines changed: 44 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,44 @@
1+
import math
2+
3+
import numpy as np
4+
from bitbots_blackboard.body_blackboard import BodyBlackboard
5+
from dynamic_stack_decider.abstract_decision_element import AbstractDecisionElement
6+
from ros2_numpy import numpify
7+
from tf_transformations import euler_from_quaternion
8+
9+
from bitbots_body_behavior.behavior_dsd.actions.go_to_block_position import GoToBlockPosition
10+
11+
12+
class OnBlockPosition(AbstractDecisionElement):
13+
blackboard: BodyBlackboard
14+
15+
def __init__(self, blackboard, dsd, parameters):
16+
super().__init__(blackboard, dsd, parameters)
17+
self.go_to_block_postion_action = GoToBlockPosition(blackboard, dsd, parameters)
18+
self.threshold = parameters.get("threshold", 0.0)
19+
self.orientation_threshold = math.radians(self.blackboard.config["goal_alignment_orientation_threshold"])
20+
21+
def perform(self, reevaluate=False):
22+
"""
23+
Determines whether we are on the block position as goalie
24+
"""
25+
self.go_to_block_postion_action.perform()
26+
current_pose = self.blackboard.world_model.get_current_position_pose_stamped()
27+
goal_pose = self.blackboard.pathfinding.get_goal()
28+
29+
if current_pose is None or goal_pose is None:
30+
return "NO"
31+
32+
current_orientation = euler_from_quaternion(numpify(current_pose.pose.orientation))
33+
goal_orientation = euler_from_quaternion(numpify(goal_pose.pose.orientation))
34+
angle_to_goal_orientation = abs(math.remainder(current_orientation[2] - goal_orientation[2], math.tau))
35+
self.publish_debug_data("current_orientation", current_orientation[2])
36+
self.publish_debug_data("goal_orientation", goal_orientation[2])
37+
self.publish_debug_data("angle_to_goal_orientation", angle_to_goal_orientation)
38+
39+
distance = np.linalg.norm(numpify(goal_pose.pose.position) - numpify(current_pose.pose.position))
40+
self.publish_debug_data("distance", distance)
41+
42+
if distance < self.threshold and angle_to_goal_orientation < self.orientation_threshold:
43+
return "YES"
44+
return "NO"

bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/decisions/reached_goal.py

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -83,7 +83,9 @@ class ReachedAndAlignedToPathPlanningGoalPosition(AbstractDecisionElement):
8383
def __init__(self, blackboard, dsd, parameters):
8484
super().__init__(blackboard, dsd, parameters)
8585
self.frame_id = parameters.get("frame_id", self.blackboard.map_frame)
86+
# on the map frame the threshold is in meters
8687
self.threshold = parameters.get("threshold")
88+
# the orientation threshold is in degrees
8789
self.orientation_threshold = math.radians(self.blackboard.config["goal_alignment_orientation_threshold"])
8890
self.latch = parameters.get("latch", False)
8991
self.latched = False

bitbots_behavior/bitbots_body_behavior/bitbots_body_behavior/behavior_dsd/main.dsd

Lines changed: 11 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,9 @@ $DoOnce
1717
#StandAndLook
1818
@ChangeAction + action:waiting, @LookAtFieldFeatures, @Stand
1919

20+
#DescendAndLook
21+
@ChangeAction + action:waiting, @LookAtFieldFeatures, @Stand + duration:1.0, @Descend
22+
2023
#GetWalkreadyAndLocalize
2124
@ChangeAction + action:waiting + r:false, @PlayAnimationInitInSim + r:false, @LookAtFieldFeatures + r:false, @GetWalkready + r:false, @WalkInPlace
2225

@@ -33,7 +36,9 @@ $DoOnce
3336
$DoOnce
3437
NOT_DONE --> @LookAtFieldFeatures, @ChangeAction + action:positioning, @GoToRolePosition + blocking:false
3538
DONE --> $ReachedAndAlignedToPathPlanningGoalPosition + threshold:0.2 + latch:true
36-
YES --> #StandAndLook
39+
YES --> $ConfigRole
40+
GOALIE --> #DescendAndLook
41+
ELSE --> #StandAndLook
3742
NO --> @LookAtFieldFeatures, @GoToRolePosition
3843

3944
#KickWithAvoidance
@@ -61,7 +66,11 @@ $GoalScoreRecently
6166
#GoalieBehavior
6267
$ClosestToBall
6368
NO --> $BallInOwnPercent + p:40
64-
YES --> @ChangeAction + action:positioning, @AvoidBallActive, @LookAtFieldFeatures, @GoToBlockPosition
69+
YES --> $DoOnce
70+
NOT_DONE --> @ChangeAction + action:positioning, @LookAtFieldFeatures, @GoToBlockPosition + blocking:false
71+
DONE --> $OnBlockPosition + threshold:0.2
72+
YES --> @Stand + duration:1.0, @Descend
73+
NO --> @GoToBlockPosition + blocking:false
6574
NO --> #RolePositionWithPause
6675
YES --> #KickWithAvoidance
6776

bitbots_motion/bitbots_hcm/bitbots_hcm/hcm_dsd/actions/play_animation.py

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -26,10 +26,10 @@ def perform(self, reevaluate=False):
2626
anim = self.choose_animation()
2727

2828
# try to start animation
29-
sucess = self.start_animation(anim)
29+
success = self.start_animation(anim)
3030

3131
# if we fail, we need to abort this action
32-
if not sucess:
32+
if not success:
3333
self.blackboard.node.get_logger().error("Could not start animation. Will abort play animation action!")
3434
return self.pop()
3535

@@ -208,7 +208,8 @@ def on_pop(self):
208208
def start_animation(self):
209209
"""
210210
This will NOT wait by itself. You have to check animation_finished() by yourself.
211-
:return:
211+
212+
:return: True if the animation was started, False if not
212213
"""
213214

214215
first_try = self.blackboard.dynup_action_client.wait_for_server(

0 commit comments

Comments
 (0)