Skip to content

Commit

Permalink
Merge branch 'main' into feature/runtime_type_checks
Browse files Browse the repository at this point in the history
  • Loading branch information
Flova authored Jan 5, 2025
2 parents 5a8445b + 1dfb041 commit 8dbc81e
Show file tree
Hide file tree
Showing 5 changed files with 61 additions and 2 deletions.
48 changes: 47 additions & 1 deletion bitbots_misc/bitbots_teleop/scripts/teleop_keyboard.py
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@

from bitbots_msgs.action import Dynup, Kick
from bitbots_msgs.msg import HeadMode, JointCommand
from bitbots_msgs.srv import SimulatorPush

msg = """
BitBots Teleop
Expand Down Expand Up @@ -57,6 +58,13 @@
4: Ball Mode adapted for Penalty Kick
5: Do a pattern which only looks in front of the robot
Pushing:
p: execute Push
Shift-p: reset Power to 0
ü/ä: increase/decrease power forward (x axis)
+/#: increase/decrease power left (y axis)
SHIFT increases/decreases with factor 10
CTRL-C to quit
Expand Down Expand Up @@ -121,6 +129,9 @@ def __init__(self):
self.th = 0
self.status = 0

self.push_force_x = 0.0
self.push_force_y = 0.0

# Head Part
self.create_subscription(JointState, "joint_states", self.joint_state_cb, 1)
self.head_mode_pub = self.create_publisher(HeadMode, "head_mode", 1)
Expand All @@ -145,6 +156,7 @@ def __init__(self):

self.reset_robot = self.create_client(Empty, "/reset_pose")
self.reset_ball = self.create_client(Empty, "/reset_ball")
self.simulator_push = self.create_client(SimulatorPush, "/simulator_push")

self.frame_prefix = "" if os.environ.get("ROS_NAMESPACE") is None else os.environ.get("ROS_NAMESPACE") + "/"

Expand Down Expand Up @@ -308,6 +320,32 @@ def loop(self):
self.z = 0
self.a_x = -1
self.th = 0
elif key == "p":
# push robot in simulation
push_request = SimulatorPush.Request()
push_request.force.x = self.push_force_x
push_request.force.y = self.push_force_y
push_request.relative = True
self.simulator_push.call_async(push_request)
elif key == "P":
self.push_force_x = 0.0
self.push_force_y = 0.0
elif key == "ü":
self.push_force_x += 1
elif key == "Ü":
self.push_force_x += 10
elif key == "ä":
self.push_force_x -= 1
elif key == "Ä":
self.push_force_x -= 10
elif key == "+":
self.push_force_y += 1
elif key == "*":
self.push_force_y += 10
elif key == "#":
self.push_force_y -= 1
elif key == "'":
self.push_force_y -= 10
else:
self.x = 0
self.y = 0
Expand All @@ -324,7 +362,15 @@ def loop(self):
twist.linear = Vector3(x=float(self.x), y=float(self.y), z=0.0)
twist.angular = Vector3(x=float(self.a_x), y=0.0, z=float(self.th))
self.pub.publish(twist)
state_str = f"x: {self.x} \ny: {self.y} \nturn: {self.th} \nhead mode: {self.head_mode_msg.head_mode} \n"
state_str = (
f"x: {self.x} \n"
f"y: {self.y} \n"
f"turn: {self.th} \n"
f"head mode: {self.head_mode_msg.head_mode} \n"
f"push force x (+forward/-back): {self.push_force_x} \n"
f"push force y (+left/-right): {self.push_force_y} "
)

for _ in range(state_str.count("\n") + 1):
sys.stdout.write("\x1b[A")
print(state_str)
Expand Down
1 change: 1 addition & 0 deletions bitbots_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,7 @@ rosidl_generate_interfaces(
"srv/SetObjectPose.srv"
"srv/SetObjectPosition.srv"
"srv/SetTeachingMode.srv"
"srv/SimulatorPush.srv"
DEPENDENCIES
action_msgs
geometry_msgs
Expand Down
4 changes: 4 additions & 0 deletions bitbots_msgs/srv/SimulatorPush.srv
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
geometry_msgs/Vector3 force
bool relative
string robot "amy"
---
1 change: 1 addition & 0 deletions bitbots_simulation/bitbots_pybullet_sim/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
<depend>python3-numpy</depend>

<export>
<build_type>ament_cmake</build_type>
<bitbots_documentation>
<status>unknown</status>
<language>python</language>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
from rosgraph_msgs.msg import Clock
from std_srvs.srv import Empty

from bitbots_msgs.srv import SetObjectPose, SetObjectPosition
from bitbots_msgs.srv import SetObjectPose, SetObjectPosition, SimulatorPush

G = 9.81

Expand Down Expand Up @@ -119,6 +119,9 @@ def __init__(
self.set_ball_position_service = self.ros_node.create_service(
SetObjectPosition, base_ns + "set_ball_position", self.ball_pos_callback
)
self.simulator_push_service = self.ros_node.create_service(
SimulatorPush, base_ns + "simulator_push", self.simulator_push
)

self.world_info = self.supervisor.getFromDef("world_info")
self.ball = self.supervisor.getFromDef("ball")
Expand Down Expand Up @@ -242,6 +245,10 @@ def robot_pose_callback(self, request=None, response=None):
)
return response or SetObjectPose.Response()

def simulator_push(self, request=None, response=None):
self.robot_nodes[request.robot].addForce([request.force.x, request.force.y, request.force.z], request.relative)
return response or Empty.Response()

def reset_ball(self, request=None, response=None):
self.ball.getField("translation").setSFVec3f([0, 0, 0.0772])
self.ball.getField("rotation").setSFRotation([0, 0, 1, 0])
Expand Down

0 comments on commit 8dbc81e

Please sign in to comment.