From d15b1d97af4bb23b305372b54f0f854bf0fac0f0 Mon Sep 17 00:00:00 2001 From: manx52 Date: Tue, 27 Aug 2024 18:09:10 -0400 Subject: [PATCH] fixed req --- requirements.txt | 2 +- .../soccer_pycontrol/src/soccer_pycontrol/main.py | 10 +++++----- .../src/soccer_pycontrol/model/model_ros/bez_ros.py | 2 +- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/requirements.txt b/requirements.txt index 2f19a379d..b9a111f7e 100644 --- a/requirements.txt +++ b/requirements.txt @@ -19,7 +19,7 @@ pygame~=2.5.0 ultralytics~=8.2.82 # Control -pinocchio==0.4.3 +pin==2.7.0 placo~=0.6.2 pybullet~=3.2.5 mujoco~=3.2.0 diff --git a/soccer_control/soccer_pycontrol/src/soccer_pycontrol/main.py b/soccer_control/soccer_pycontrol/src/soccer_pycontrol/main.py index ae6fb927a..fe7945740 100755 --- a/soccer_control/soccer_pycontrol/src/soccer_pycontrol/main.py +++ b/soccer_control/soccer_pycontrol/src/soccer_pycontrol/main.py @@ -2,7 +2,7 @@ import psutil from soccer_pycontrol.model.model_ros.bez_ros import BezROS -from soccer_pycontrol.walk_engine.walk_engine_ros.walk_engine_ros import WalkEngineROS +from soccer_pycontrol.walk_engine.walk_engine_ros.walk_engine_ros import WalkEngineRos pid = psutil.Process() try: @@ -23,11 +23,11 @@ if __name__ == "__main__": rospy.init_node("soccer_control") rospy.loginfo("Initializing Soccer Control") - bez = BezROS() - walker = WalkEngineROS(bez) - # walker = NavigatorRos() + ns = "/robot1/" + bez = BezROS(ns=ns) + walker = WalkEngineRos(bez) rospy.loginfo("Starting Control Loop") try: - walker.run() + walker.walk(d_x=0.00, t_goal=10) except rospy.exceptions.ROSException as ex: exit(0) diff --git a/soccer_control/soccer_pycontrol/src/soccer_pycontrol/model/model_ros/bez_ros.py b/soccer_control/soccer_pycontrol/src/soccer_pycontrol/model/model_ros/bez_ros.py index c967e239a..e2e27be0b 100644 --- a/soccer_control/soccer_pycontrol/src/soccer_pycontrol/model/model_ros/bez_ros.py +++ b/soccer_control/soccer_pycontrol/src/soccer_pycontrol/model/model_ros/bez_ros.py @@ -12,7 +12,7 @@ class BezROS(Bez): def __init__(self, ns: str = ""): self.ns = ns - self.robot_model = rospy.get_param("robot_model", "bez2") + self.robot_model = rospy.get_param("robot_model", "bez1") if rospy.get_param("/use_sim_time", False): sim = "_sim" else: