Skip to content

Commit aa0d602

Browse files
a11delavarSF-Sudio
andcommitted
Implement Mujoco Simulator
Co-authored-by: Samim Maschal <[email protected]> Co-authored-by: Sebastian Fromm <[email protected]>
1 parent 55613b8 commit aa0d602

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

75 files changed

+1200
-2
lines changed

bitbots_misc/bitbots_bringup/launch/simulator_teamplayer.launch

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,10 +10,15 @@
1010
<arg name="teamcom" default="false" description="Whether the team communication system should be started" />
1111
<arg name="vision" default="true" description="Whether the vision system should be started" />
1212
<arg name="world_model" default="true" description="Whether the world model should be started"/>
13+
<arg name="mujoco" default="false" description="Whether to use the Mujoco simulator instead of Webots"/>
1314

1415
<!-- load the general simulator -->
15-
<include file="$(find-pkg-share bitbots_webots_sim)/launch/simulation.launch" />
16-
16+
<group if="$(var mujoco)">
17+
<node pkg="bitbots_mujoco_sim" exec="sim" name="mujoco_simulation_node" output="screen"/>
18+
</group>
19+
<group unless="$(var mujoco)">
20+
<include file="$(find-pkg-share bitbots_webots_sim)/launch/simulation.launch" />
21+
</group>
1722
<!-- load teamplayer software stack -->
1823
<include file="$(find-pkg-share bitbots_bringup)/launch/teamplayer.launch">
1924
<arg name="behavior" value="$(var behavior)" />
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
"""BitBots MuJoCo Simulation Package"""
2+
3+
__all__ = [
4+
"simulation",
5+
]
Lines changed: 55 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,55 @@
1+
import mujoco
2+
import numpy as np
3+
4+
5+
class Camera:
6+
"""Represents a camera in the MuJoCo simulation, providing image rendering capabilities."""
7+
8+
def __init__(self, model: mujoco.MjModel, data: mujoco.MjData, name: str, width: int = 800, height: int = 600):
9+
self.model: mujoco.MjModel = model
10+
self.data: mujoco.MjData = data
11+
self.name: str = name
12+
self.instance = model.camera(name)
13+
self.width: int = width
14+
self.height: int = height
15+
self.renderer = mujoco.Renderer(self.model, height=self.height, width=self.width)
16+
17+
@property
18+
def fov(self) -> float:
19+
"""Returns the camera's horizontal field of view in radians."""
20+
if hasattr(self, "_fov") and self._fov is not None:
21+
return self._fov
22+
23+
# MuJoCo uses fovy (vertical field of view in degrees)
24+
fovy_deg = self.instance.fovy[0] if hasattr(self.instance.fovy, "__iter__") else self.instance.fovy
25+
fovy_rad = np.deg2rad(fovy_deg)
26+
27+
# Convert vertical FOV to horizontal FOV using aspect ratio
28+
aspect_ratio = self.width / self.height
29+
fovx_rad = 2 * np.arctan(np.tan(fovy_rad / 2) * aspect_ratio)
30+
31+
self._fov = fovx_rad
32+
return self._fov
33+
34+
def render(self) -> bytes:
35+
"""
36+
Renders and returns the camera image as raw bytes (BGRA format).
37+
Returns Raw image data in BGRA8 format for ROS Image messages.
38+
"""
39+
# Update renderer with current scene
40+
self.renderer.update_scene(self.data, camera=self.name)
41+
42+
# Render the image - returns RGB by default
43+
rgb_array = self.renderer.render()
44+
45+
# Convert RGB to BGRA (standard for ROS Image messages)
46+
# MuJoCo returns RGB uint8 array of shape (height, width, 3)
47+
# We need to add alpha channel and swap R and B
48+
height, width, _ = rgb_array.shape
49+
bgra_array = np.zeros((height, width, 4), dtype=np.uint8)
50+
bgra_array[:, :, 0] = rgb_array[:, :, 2] # B
51+
bgra_array[:, :, 1] = rgb_array[:, :, 1] # G
52+
bgra_array[:, :, 2] = rgb_array[:, :, 0] # R
53+
bgra_array[:, :, 3] = 255 # A (fully opaque)
54+
55+
return bgra_array.tobytes()
Lines changed: 39 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,39 @@
1+
import mujoco
2+
3+
4+
class Joint:
5+
"""Represents a single controllable joint and associated actuator in the MuJoCo simulation."""
6+
7+
def __init__(
8+
self,
9+
model: mujoco.MjModel,
10+
data: mujoco.MjData,
11+
ros_name: str,
12+
name: str | None = None,
13+
):
14+
self.model: mujoco.MjModel = model
15+
self.data: mujoco.MjData = data
16+
self.ros_name: str = ros_name
17+
self.name: str = name if name is not None else ros_name
18+
self.joint_instance: int = model.joint(self.name)
19+
self.actuator_instance: int = model.actuator(self.name)
20+
21+
@property
22+
def position(self) -> float:
23+
"""Gets the current joint position (angle) in radians."""
24+
return self.data.qpos[self.joint_instance.qposadr[0]]
25+
26+
@position.setter
27+
def position(self, value: float) -> None:
28+
"""Sets the position target for the joint's position actuator."""
29+
self.data.ctrl[self.actuator_instance.id] = value
30+
31+
@property
32+
def velocity(self) -> float:
33+
"""Gets the current joint velocity in rad/s."""
34+
return self.data.qvel[self.joint_instance.dofadr[0]]
35+
36+
@property
37+
def effort(self) -> float:
38+
"""Gets the current effort (force/torque) applied by the position actuator."""
39+
return self.data.actuator_force[self.actuator_instance.id]
Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
import threading
2+
3+
import rclpy
4+
from rclpy.experimental.events_executor import EventsExecutor
5+
6+
from bitbots_mujoco_sim.simulation import Simulation
7+
8+
9+
def main(args=None):
10+
rclpy.init(args=args)
11+
simulation = Simulation()
12+
executor = EventsExecutor()
13+
executor.add_node(simulation)
14+
thread = threading.Thread(target=executor.spin, daemon=True)
15+
thread.start()
16+
simulation.run()
17+
simulation.destroy_node()
18+
rclpy.shutdown()
Lines changed: 83 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,83 @@
1+
import mujoco
2+
3+
from bitbots_mujoco_sim.camera import Camera
4+
from bitbots_mujoco_sim.joint import Joint
5+
from bitbots_mujoco_sim.sensor import Sensor
6+
7+
8+
class Robot:
9+
"""Represents the robot, holding all its components like the camera, joints, and sensors."""
10+
11+
def __init__(self, model: mujoco.MjModel, data: mujoco.MjData):
12+
self.camera = Camera(model, data, name="head_camera")
13+
self.joints = RobotJoints(
14+
[
15+
# --- Right Leg ---
16+
Joint(model, data, ros_name="RHipYaw"),
17+
Joint(model, data, ros_name="RHipRoll"),
18+
Joint(model, data, ros_name="RHipPitch"),
19+
Joint(model, data, ros_name="RKnee"),
20+
Joint(model, data, ros_name="RAnklePitch"),
21+
Joint(model, data, ros_name="RAnkleRoll"),
22+
# --- Left Leg ---
23+
Joint(model, data, ros_name="LHipYaw"),
24+
Joint(model, data, ros_name="LHipRoll"),
25+
Joint(model, data, ros_name="LHipPitch"),
26+
Joint(model, data, ros_name="LKnee"),
27+
Joint(model, data, ros_name="LAnklePitch"),
28+
Joint(model, data, ros_name="LAnkleRoll"),
29+
# --- Arms ---
30+
Joint(model, data, ros_name="RShoulderPitch"),
31+
Joint(model, data, ros_name="RShoulderRoll"),
32+
Joint(model, data, ros_name="RElbow"),
33+
Joint(model, data, ros_name="LShoulderPitch"),
34+
Joint(model, data, ros_name="LShoulderRoll"),
35+
Joint(model, data, ros_name="LElbow"),
36+
# --- Head ---
37+
Joint(model, data, ros_name="HeadPan"),
38+
Joint(model, data, ros_name="HeadTilt"),
39+
]
40+
)
41+
self.sensors = RobotSensors(
42+
[
43+
# IMU Sensors
44+
Sensor(model, data, name="gyro", ros_name="IMU_gyro"),
45+
Sensor(model, data, name="accelerometer", ros_name="IMU_accelerometer"),
46+
Sensor(
47+
model,
48+
data,
49+
name="orientation",
50+
ros_name="IMU_orientation",
51+
), # Global orientation quaternion
52+
Sensor(model, data, name="position", ros_name="IMU_position"), # Global position vector
53+
# Foot Sensors
54+
Sensor(model, data, name="l_foot_pos", ros_name="left_foot_position"),
55+
Sensor(model, data, name="r_foot_pos", ros_name="right_foot_position"),
56+
Sensor(model, data, name="l_foot_global_linvel", ros_name="left_foot_velocity"),
57+
Sensor(model, data, name="r_foot_global_linvel", ros_name="right_foot_velocity"),
58+
]
59+
)
60+
61+
62+
class RobotSensors(list[Sensor]):
63+
"""A list of Robot Sensors with additional helper methods."""
64+
65+
def get(self, name: str) -> Joint:
66+
"""Finds and returns a specific joint by its ROS name."""
67+
return next(filter(lambda joint: joint.ros_name == name, self))
68+
69+
@property
70+
def gyro(self) -> Sensor:
71+
return self.get("IMU_gyro")
72+
73+
@property
74+
def accelerometer(self) -> Sensor:
75+
return self.get("IMU_accelerometer")
76+
77+
78+
class RobotJoints(list[Joint]):
79+
"""A list of Robot Joints with additional helper methods."""
80+
81+
def get(self, name: str) -> Joint:
82+
"""Finds and returns a specific joint by its ROS name."""
83+
return next(filter(lambda joint: joint.ros_name == name, self))
Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
1+
import mujoco
2+
import numpy as np
3+
4+
5+
class Sensor:
6+
"""Represents a single sensor, providing a clean interface to its value."""
7+
8+
def __init__(self, model: mujoco.MjModel, data: mujoco.MjData, name: str, ros_name: str):
9+
self._data = data
10+
self.ros_name: str = ros_name
11+
self.instance: int = model.sensor(name)
12+
self.id: int = self.instance.id
13+
14+
@property
15+
def data(self) -> np.ndarray:
16+
"""Gets the current sensor reading from sensordata array."""
17+
return self._data.sensordata[self.adr : self.adr + self.dim]
18+
19+
@property
20+
def adr(self) -> int:
21+
"""Gets the address of the sensor data in sensordata array."""
22+
return int(self.instance.adr)
23+
24+
@property
25+
def dim(self) -> int:
26+
"""Gets the dimension of the sensor data."""
27+
return int(self.instance.dim)

0 commit comments

Comments
 (0)