2222import onnxruntime as rt
2323from ament_index_python import get_package_share_directory
2424from geometry_msgs .msg import PoseStamped , Twist
25+ from rclpy .experimental .events_executor import EventsExecutor
2526from rclpy .node import Node
2627from sensor_msgs .msg import Imu , JointState
2728from transforms3d .euler import euler2mat
2829from transforms3d .quaternions import quat2mat
2930
3031from bitbots_msgs .msg import JointCommand
3132
32- ONNX_MODEL = os .path .join (get_package_share_directory ("bitbots_rl_walk" ), "models" , "wolfgang_forward_kick_better_ball_ppo.onnx" )
33+ ONNX_MODEL = os .path .join (
34+ get_package_share_directory ("bitbots_rl_walk" ), "models" , "wolfgang_forward_kick_better_ball_ppo.onnx"
35+ )
3336
3437WALKREADY_STATE = np .array (
3538 [
@@ -198,7 +201,7 @@ def _timer_callback(self):
198201
199202 phase = np .array ([np .cos (self ._phase ), np .sin (self ._phase )], dtype = np .float32 ).flatten ()
200203
201- command = np .array ([self ._cmd_vel .linear .x , self ._cmd_vel .linear .y , self ._cmd_vel .angular .z ], dtype = np .float32 )
204+ # command = np.array([self._cmd_vel.linear.x, self._cmd_vel.linear.y, self._cmd_vel.angular.z], dtype=np.float32)
202205
203206 rel_ball_pos = np .array (
204207 [
@@ -212,7 +215,7 @@ def _timer_callback(self):
212215 [
213216 gyro , # 3
214217 gravity , # 4
215- command , # 3
218+ # command, # 3
216219 joint_angles , # 18
217220 joint_velocities , # 18
218221 self ._previous_action , # 18 # Previous action
@@ -246,6 +249,11 @@ def main():
246249
247250 rclpy .init ()
248251 node = KickNode ()
249- rclpy .spin (node )
252+ executor = EventsExecutor ()
253+ executor .add_node (node )
254+ try :
255+ executor .spin (node )
256+ except KeyboardInterrupt :
257+ pass
258+
250259 node .destroy_node ()
251- rclpy .try_shutdown ()
0 commit comments