Skip to content

Commit 2b71f98

Browse files
committed
Implement Mujoco Simulator
1 parent 55613b8 commit 2b71f98

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

+1190
-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: 59 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,59 @@
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 = (
25+
self.instance.fovy[0]
26+
if hasattr(self.instance.fovy, "__iter__")
27+
else self.instance.fovy
28+
)
29+
fovy_rad = np.deg2rad(fovy_deg)
30+
31+
# Convert vertical FOV to horizontal FOV using aspect ratio
32+
aspect_ratio = self.width / self.height
33+
fovx_rad = 2 * np.arctan(np.tan(fovy_rad / 2) * aspect_ratio)
34+
35+
self._fov = fovx_rad
36+
return self._fov
37+
38+
def render(self) -> bytes:
39+
"""
40+
Renders and returns the camera image as raw bytes (BGRA format).
41+
Returns Raw image data in BGRA8 format for ROS Image messages.
42+
"""
43+
# Update renderer with current scene
44+
self.renderer.update_scene(self.data, camera=self.name)
45+
46+
# Render the image - returns RGB by default
47+
rgb_array = self.renderer.render()
48+
49+
# Convert RGB to BGRA (standard for ROS Image messages)
50+
# MuJoCo returns RGB uint8 array of shape (height, width, 3)
51+
# We need to add alpha channel and swap R and B
52+
height, width, _ = rgb_array.shape
53+
bgra_array = np.zeros((height, width, 4), dtype=np.uint8)
54+
bgra_array[:, :, 0] = rgb_array[:, :, 2] # B
55+
bgra_array[:, :, 1] = rgb_array[:, :, 1] # G
56+
bgra_array[:, :, 2] = rgb_array[:, :, 0] # R
57+
bgra_array[:, :, 3] = 255 # A (fully opaque)
58+
59+
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: 78 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,78 @@
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(model, data, name="orientation", ros_name="IMU_orientation",), # Global orientation quaternion
47+
Sensor(model, data, name="position", ros_name="IMU_position"), # Global position vector
48+
# Foot Sensors
49+
Sensor(model, data, name="l_foot_pos", ros_name="left_foot_position"),
50+
Sensor(model, data, name="r_foot_pos", ros_name="right_foot_position"),
51+
Sensor(model, data, name="l_foot_global_linvel", ros_name="left_foot_velocity"),
52+
Sensor(model, data, name="r_foot_global_linvel", ros_name="right_foot_velocity"),
53+
]
54+
)
55+
56+
57+
class RobotSensors(list[Sensor]):
58+
"""A list of Robot Sensors with additional helper methods."""
59+
60+
def get(self, name: str) -> Joint:
61+
"""Finds and returns a specific joint by its ROS name."""
62+
return next(filter(lambda joint: joint.ros_name == name, self))
63+
64+
@property
65+
def gyro(self) -> Sensor:
66+
return self.get("IMU_gyro")
67+
68+
@property
69+
def accelerometer(self) -> Sensor:
70+
return self.get("IMU_accelerometer")
71+
72+
73+
class RobotJoints(list[Joint]):
74+
"""A list of Robot Joints with additional helper methods."""
75+
76+
def get(self, name: str) -> Joint:
77+
"""Finds and returns a specific joint by its ROS name."""
78+
return next(filter(lambda joint: joint.ros_name == name, self))
Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,28 @@
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)
28+
Lines changed: 160 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,160 @@
1+
import time
2+
import math
3+
4+
import mujoco
5+
from ament_index_python.packages import get_package_share_directory
6+
from mujoco import viewer
7+
from rclpy.node import Node
8+
from rclpy.time import Time
9+
from rosgraph_msgs.msg import Clock
10+
from sensor_msgs.msg import CameraInfo, Imu, JointState, Image
11+
12+
from bitbots_msgs.msg import JointCommand
13+
from bitbots_mujoco_sim.Robot import Robot
14+
15+
16+
class Simulation(Node):
17+
"""Manages the MuJoCo simulation state and its components."""
18+
19+
def __init__(self):
20+
super().__init__("sim_interface")
21+
package_path = get_package_share_directory("bitbots_mujoco_sim")
22+
self.model: mujoco.MjModel = mujoco.MjModel.from_xml_path(package_path + "/xml/adult_field.xml")
23+
self.data: mujoco.MjData = mujoco.MjData(self.model)
24+
self.robot: Robot = Robot(self.model, self.data)
25+
26+
self.time = 0.0
27+
self.time_message = Time(seconds=0, nanoseconds=0).to_msg()
28+
self.timestep = self.model.opt.timestep
29+
self.step_number = 0
30+
self.clock_publisher = self.create_publisher(Clock, "clock", 1)
31+
32+
self.js_publisher = self.create_publisher(JointState, "joint_states", 1)
33+
self.create_subscription(JointCommand, "DynamixelController/command", self.joint_command_callback, 1)
34+
35+
self.imu_frame_id = self.get_parameter_or("imu_frame", "imu_frame")
36+
self.imu_publisher = self.create_publisher(Imu, "imu/data_raw", 1)
37+
38+
self.camera_active = True
39+
self.camera_optical_frame_id = self.get_parameter_or("camera_optical_frame", "camera_optical_frame")
40+
self.camera_publisher = self.create_publisher(Image, "camera/image_proc", 1)
41+
self.camera_info_publisher = self.create_publisher(CameraInfo, "camera/camera_info", 1)
42+
43+
self.events = {
44+
"clock": {"frequency": 1, "handler": self.publish_clock_event},
45+
"joint_states": {"frequency": 3, "handler": self.publish_ros_joint_states_event},
46+
"imu": {"frequency": 3, "handler": self.publish_imu_event},
47+
"camera": {"frequency": 24, "handler": self.publish_camera_event},
48+
}
49+
50+
def run(self) -> None:
51+
print("Starting simulation viewer...")
52+
with viewer.launch_passive(self.model, self.data) as view:
53+
while view.is_running():
54+
self.step()
55+
view.sync()
56+
57+
def joint_command_callback(self, command: JointCommand) -> None:
58+
if len(command.positions) != 0:
59+
for i in range(len(command.joint_names)):
60+
joint = self.robot.joints.get(command.joint_names[i])
61+
joint.position = command.positions[i]
62+
#if len(command.velocities) != 0:
63+
# joint.velocity = command.velocities[i]
64+
65+
def step(self) -> None:
66+
real_start_time = time.time()
67+
self.step_number += 1
68+
self.time += self.timestep
69+
self.time_message = Time(seconds=int(self.time), nanoseconds=int(self.time % 1 * 1e9)).to_msg()
70+
71+
mujoco.mj_step(self.model, self.data)
72+
73+
for event_name, event_config in self.events.items():
74+
if self.step_number % event_config["frequency"] == 0:
75+
event_config["handler"]()
76+
77+
real_end_time = time.time()
78+
time.sleep(max(0.0, self.timestep - (real_end_time - real_start_time)))
79+
80+
def publish_clock_event(self) -> None:
81+
clock_msg = Clock()
82+
clock_msg.clock = self.time_message
83+
self.clock_publisher.publish(clock_msg)
84+
85+
def publish_ros_joint_states_event(self) -> None:
86+
js = JointState()
87+
js.name = []
88+
js.header.stamp = self.time_message
89+
js.position = []
90+
js.effort = []
91+
for joint in self.robot.joints:
92+
js.name.append(joint.ros_name)
93+
js.position.append(joint.position)
94+
js.velocity.append(joint.velocity)
95+
js.effort.append(joint.effort)
96+
self.js_publisher.publish(js)
97+
98+
def publish_imu_event(self) -> None:
99+
imu = Imu()
100+
imu.header.stamp = self.time_message
101+
imu.header.frame_id = self.imu_frame_id
102+
imu.linear_acceleration.x, imu.linear_acceleration.y, imu.linear_acceleration.z = self.robot.sensors.accelerometer.data
103+
104+
# make sure that acceleration is not completely zero or we will get error in filter.
105+
# Happens if robot is moved manually in the simulation
106+
if imu.linear_acceleration.x == 0 and imu.linear_acceleration.y == 0 and imu.linear_acceleration.z == 0:
107+
imu.linear_acceleration.z = 0.001
108+
109+
imu.angular_velocity.x, imu.angular_velocity.y, imu.angular_velocity.z = self.robot.sensors.gyro.data
110+
111+
self.imu_publisher.publish(imu)
112+
113+
def publish_camera_event(self) -> None:
114+
if not self.camera_active:
115+
return
116+
117+
img = Image()
118+
img.header.stamp = self.time_message
119+
img.header.frame_id = self.camera_optical_frame_id
120+
img.encoding = "bgra8"
121+
img.height = self.robot.camera.height
122+
img.width = self.robot.camera.width
123+
img.step = 4 * self.robot.camera.width
124+
img.data = self.robot.camera.render()
125+
self.camera_publisher.publish(img)
126+
127+
cam_info = CameraInfo()
128+
cam_info.header = img.header
129+
cam_info.height = self.robot.camera.height
130+
cam_info.width = self.robot.camera.width
131+
132+
@staticmethod
133+
def focal_length_from_fov(fov: float, resolution: int) -> float:
134+
"Calculate focal length from field of view and resolution."
135+
return 0.5 * resolution * (math.cos(fov / 2) / math.sin(fov / 2))
136+
137+
@staticmethod
138+
def h_fov_to_v_fov(h_fov: float, height: int, width: int) -> float:
139+
"Convert horizontal FOV to vertical FOV based on image aspect ratio."
140+
return 2 * math.atan(math.tan(h_fov * 0.5) * (height / width))
141+
142+
camera = self.robot.camera
143+
144+
h_fov = camera.fov
145+
v_fov = h_fov_to_v_fov(h_fov, camera.height, camera.width)
146+
147+
f_x, f_y = focal_length_from_fov(h_fov, camera.width), focal_length_from_fov(v_fov, camera.height)
148+
cx, cy = camera.width / 2.0, camera.height / 2.0
149+
cam_info.k = [
150+
f_x, 0.0, cx,
151+
0.0, f_y, cy,
152+
0.0, 0.0, 1.0
153+
]
154+
cam_info.p = [
155+
f_x, 0.0, cx, 0.0,
156+
0.0, f_y, cy, 0.0,
157+
0.0, 0.0, 1.0, 0.0
158+
]
159+
160+
self.camera_info_publisher.publish(cam_info)
Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
"""BitBots MuJoCo Simulation Package"""
2+
3+
from .Simulation import Simulation
4+
5+
__all__ = [
6+
"Simulation",
7+
]

0 commit comments

Comments
 (0)