Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions examples/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,3 +9,4 @@ Examples Overview:
* `lgsvl`: Examples for the LGSVL simulator
* `visualizer`: Examples for the built in Scenic visualizer
* `webots`: Examples for the Webots robotics simulator
* `mujoco`: Examples for the MuJoCo physics simulator
7 changes: 7 additions & 0 deletions examples/mujoco/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
# MuJoCo Examples

To run the examples, type `mjpython -m` prior to the Scenic command, i.e.,

```
mjpython -m scenic -S farm-ng/example_simulation.scenic
```
202 changes: 202 additions & 0 deletions examples/mujoco/farm-ng/amiga.scenic
Original file line number Diff line number Diff line change
@@ -0,0 +1,202 @@
from scenic.simulators.mujoco.model import MujocoBody, DynamicMujocoBody

class Amiga(DynamicMujocoBody):

# Scenic property - can be overridden in .scenic files.
semanticColor: [255, 0, 0] # Default green.

def __init__(self, *args, **kwargs):
super().__init__(*args, **kwargs)
self.instance_id = None
# For torque control.
self.target_velocity = 0.0 # Target wheel velocity (rad/s).
self.kp = 50.0 # Proportional gain for velocity control.
self.kd = 5.0 # Derivative gain for damping.

def semanticColorForGeom(self, geom_name):
"""
Return semantic color for a specific geom.

This allows custom coloring of different parts of the Amiga.
Override this method or use the default semanticColor for all geoms.

Args:
geom_name: Name of the geometry (e.g., "fl_wheel_amiga_0", "rail_left_amiga_0")

Returns:
[R, G, B] color list, or None to use default semanticColor
"""
# Example: Color wheels differently from the frame.
if 'wheel' in geom_name.lower():
return [50, 50, 50] # Dark gray for wheels.

# # Example: Color rails and crossbars with frame color.
# if any(part in geom_name.lower() for part in ['rail', 'crossbar', 'control_head']):
# return [200, 200, 200] # Light gray for structure

# # Example: Color module sides.
# if 'module_side' in geom_name.lower():
# return [220, 220, 210] # Off-white for module sides

# Default: use the object's semanticColor.
return None

def get_mujoco_xml(self, obj_counter, position, quaternion):
u_id = f"amiga_{obj_counter}"

# Dedicated chassis body for the camera.
self.body_name = f"chassis_{u_id}"
self.instance_id = u_id

complete_xml = f'''
<body name="root_{u_id}" pos="{position}" quat="{quaternion}">
<freejoint name="root_joint_{u_id}"/>

<body name="{self.body_name}" pos="0 0 0">
<geom name="rail_left_{u_id}" type="box" size="0.60 0.04 0.04" pos="0 0.32 0.50" rgba="0.2 0.2 0.25 1" mass="2"/>
<geom name="rail_right_{u_id}" type="box" size="0.60 0.04 0.04" pos="0 -0.32 0.50" rgba="0.2 0.2 0.25 1" mass="2"/>

<geom name="crossbar_front_{u_id}" type="box" size="0.04 0.52 0.04" pos=" 0.60 0 1.34" rgba="0.2 0.2 0.25 1" mass="1"/>
<geom name="crossbar_rear_{u_id}" type="box" size="0.04 0.52 0.04" pos="-0.60 0 1.34" rgba="0.2 0.2 0.25 1" mass="1"/>

<geom name="control_head_{u_id}" type="box" size="0.10 0.07 0.05" pos="0.45 0.35 0.95" rgba="0.1 0.1 0.1 1" mass="0.5"/>

<site name="gps_site_{u_id}" pos="0.00 0.00 0.98" size="0.01" rgba="0 1 0 0"/>
<site name="imu_site_{u_id}" pos="0.05 0.00 0.95" size="0.01" rgba="1 0 0 0"/>
<site name="front_mount_{u_id}" pos="0.70 0.00 0.74" size="0.01" rgba="0 0.6 1 0"/>
<site name="rear_mount_{u_id}" pos="-0.70 0.00 0.74" size="0.01" rgba="0 0.6 1 0"/>
</body>

<body name="fl_module_{u_id}" pos=" 0.60 0.50 0.40">
<geom name="fl_module_side1_{u_id}" type="box" size="0.20 0.02 0.45" pos="0.00 0.09 0.45" rgba="0.92 0.92 0.90 1" mass="3"/>
<geom name="fl_module_side2_{u_id}" type="box" size="0.20 0.02 0.45" pos="0.00 -0.09 0.45" rgba="0.92 0.92 0.90 1" mass="3"/>
<body name="fl_wheel_body_{u_id}" pos="0 0 0">
<joint name="fl_axle_{u_id}" type="hinge" axis="0 1 0" damping="1.0" limited="false"/>
<geom name="fl_wheel_{u_id}" type="cylinder" size="0.40 0.06" euler="-90 0 0" mass="15" friction="0.9 0.005 0.0001" rgba="0.1 0.1 0.1 1"/>
</body>
</body>

<body name="rl_module_{u_id}" pos="-0.60 0.50 0.40">
<geom name="rl_module_side1_{u_id}" type="box" size="0.20 0.02 0.45" pos="0.00 0.09 0.45" rgba="0.92 0.92 0.90 1" mass="3"/>
<geom name="rl_module_side2_{u_id}" type="box" size="0.20 0.02 0.45" pos="0.00 -0.09 0.45" rgba="0.92 0.92 0.90 1" mass="3"/>
<body name="rl_wheel_body_{u_id}" pos="0 0 0">
<joint name="rl_axle_{u_id}" type="hinge" axis="0 1 0" damping="1.0" limited="false"/>
<geom name="rl_wheel_{u_id}" type="cylinder" size="0.40 0.06" euler="-90 0 0" mass="15" friction="0.9 0.005 0.0001" rgba="0.1 0.1 0.1 1"/>
</body>
</body>

<body name="fr_module_{u_id}" pos=" 0.60 -0.50 0.40">
<geom name="fr_module_side1_{u_id}" type="box" size="0.20 0.02 0.45" pos="0.00 0.09 0.45" rgba="0.92 0.92 0.90 1" mass="3"/>
<geom name="fr_module_side2_{u_id}" type="box" size="0.20 0.02 0.45" pos="0.00 -0.09 0.45" rgba="0.92 0.92 0.90 1" mass="3"/>
<body name="fr_wheel_body_{u_id}" pos="0 0 0">
<joint name="fr_axle_{u_id}" type="hinge" axis="0 1 0" damping="1.0" limited="false"/>
<geom name="fr_wheel_{u_id}" type="cylinder" size="0.40 0.06" euler="-90 0 0" mass="15" friction="0.9 0.005 0.0001" rgba="0.1 0.1 0.1 1"/>
</body>
</body>

<body name="rr_module_{u_id}" pos="-0.60 -0.50 0.40">
<geom name="rr_module_side1_{u_id}" type="box" size="0.20 0.02 0.45" pos="0.00 0.09 0.45" rgba="0.92 0.92 0.90 1" mass="3"/>
<geom name="rr_module_side2_{u_id}" type="box" size="0.20 0.02 0.45" pos="0.00 -0.09 0.45" rgba="0.92 0.92 0.90 1" mass="3"/>
<body name="rr_wheel_body_{u_id}" pos="0 0 0">
<joint name="rr_axle_{u_id}" type="hinge" axis="0 1 0" damping="1.0" limited="false"/>
<geom name="rr_wheel_{u_id}" type="cylinder" size="0.40 0.06" euler="-90 0 0" mass="15" friction="0.9 0.005 0.0001" rgba="0.1 0.1 0.1 1"/>
</body>
</body>
</body>

<actuators>
<motor name="fl_motor_{u_id}" joint="fl_axle_{u_id}" gear="1" ctrllimited="true" ctrlrange="-100 100"/>
<motor name="rl_motor_{u_id}" joint="rl_axle_{u_id}" gear="1" ctrllimited="true" ctrlrange="-100 100"/>
<motor name="fr_motor_{u_id}" joint="fr_axle_{u_id}" gear="1" ctrllimited="true" ctrlrange="-100 100"/>
<motor name="rr_motor_{u_id}" joint="rr_axle_{u_id}" gear="1" ctrllimited="true" ctrlrange="-100 100"/>
</actuators>

<sensors>
<accelerometer name="imu_acc_{u_id}" site="imu_site_{u_id}"/>
<gyro name="imu_gyro_{u_id}" site="imu_site_{u_id}"/>
<user name="speed_user_{u_id}" dim="1"/>
</sensors>'''

return complete_xml

def control(self, model, data):
"""Apply PD control to achieve target velocity with torque actuators."""
if not hasattr(self, 'target_velocities') or not self.target_velocities:
return

if not hasattr(self, 'instance_id') or not self.instance_id:
return

fl_target, rl_target, fr_target, rr_target = self.target_velocities

try:
# Get joint indices.
fl_joint_id = model.joint(f'fl_axle_{self.instance_id}').id
rl_joint_id = model.joint(f'rl_axle_{self.instance_id}').id
fr_joint_id = model.joint(f'fr_axle_{self.instance_id}').id
rr_joint_id = model.joint(f'rr_axle_{self.instance_id}').id

# Get actuator indices.
fl_idx = model.actuator(f'fl_motor_{self.instance_id}').id
rl_idx = model.actuator(f'rl_motor_{self.instance_id}').id
fr_idx = model.actuator(f'fr_motor_{self.instance_id}').id
rr_idx = model.actuator(f'rr_motor_{self.instance_id}').id

# Get current velocities.
fl_vel = data.qvel[fl_joint_id]
rl_vel = data.qvel[rl_joint_id]
fr_vel = data.qvel[fr_joint_id]
rr_vel = data.qvel[rr_joint_id]

# PD control: torque = kp * (target - current) - kd * current.
# Simple proportional control with velocity damping.
data.ctrl[fl_idx] = self.kp * (fl_target - fl_vel) - self.kd * fl_vel
data.ctrl[rl_idx] = self.kp * (rl_target - rl_vel) - self.kd * rl_vel
data.ctrl[fr_idx] = self.kp * (fr_target - fr_vel) - self.kd * fr_vel
data.ctrl[rr_idx] = self.kp * (rr_target - rr_vel) - self.kd * rr_vel

except Exception as e:
pass


class Plant(MujocoBody):

# Scenic property - can be overridden in .scenic files.
semanticColor: [0, 255, 0] # Default green.

def __init__(self, *args, **kwargs):
super().__init__(*args, **kwargs)
self.instance_id = None

def semanticColorForGeom(self, geom_name):
"""Return semantic color for a specific geom of the plant.

Args:
geom_name: Name of the geometry (e.g., "stem_plant_0", "leaf_plant_0")

Returns:
[R, G, B] color list, or None to use default semanticColor
"""
# Example: Color stem differently from leaves.
if 'stem' in geom_name.lower():
return [139, 69, 19] # Brown for stem.

if 'leaf' in geom_name.lower():
return [34, 139, 34] # Forest green for leaves.

# Default: use the object's semanticColor.
return None

def get_mujoco_xml(self, obj_counter, position, quaternion):

u_id = f"plant_{obj_counter}"
self.instance_id = u_id
self.body_name = f"frame_{u_id}"

complete_xml = f'''
<body name="{self.body_name}" pos="{position}">
<geom name="stem_{u_id}" type="cylinder" size="0.02 0.22" pos="0 0 0.12" rgba="0.22 0.55 0.22 1" contype="1" conaffinity="1"/>
<geom name="leaf_{u_id}" type="sphere" size="0.05" pos="0 0 0.28" rgba="0.20 0.65 0.20 1" contype="1" conaffinity="1"/>
</body>'''

return complete_xml
73 changes: 73 additions & 0 deletions examples/mujoco/farm-ng/amiga_base.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,73 @@
<?xml version="1.0" encoding="utf-8"?>
<mujoco model="amiga_like_modular">
<!-- Change timestep at own risk. -->
<option timestep="0.002" gravity="0 0 -9.81" integrator="RK4"/>
<size nkey="256" nuser_sensor="1"/>
<visual>
<global offwidth="1024" offheight="768"/>
</visual>


<default>
<!-- Slightly grippy soil; tweak to taste. -->
<geom condim="4" friction="1.2 0.02 0.002"/>
<joint armature="0.0005" damping="0.1"/>
</default>

<asset>
<texture type="skybox" builtin="gradient" rgb1=".75 .92 1.00" rgb2=".60 .85 1.00" width="512" height="512"/>
<texture name="groundtex" type="2d" builtin="checker" rgb1=".55 .45 .35" rgb2=".45 .35 .25" width="1024" height="1024"/>
<material name="groundmat" texture="groundtex" texrepeat="30 30" reflectance="0.05"/>

<!-- Extra materials for crops/soil rows. -->
<material name="rowsoil" texture="groundtex" texrepeat="40 40" rgba="0.65 0.55 0.40 1" reflectance="0.02"/>
<material name="leaf" rgba="0.20 0.65 0.20 1"/>
<material name="stalk" rgba="0.22 0.55 0.22 1"/>
</asset>

<worldbody>
<!-- Light + floor so it’s bright and visible. -->
<light name="sun" pos="2 2 5" dir="-0.4 -0.4 -1"
diffuse="1 1 1" specular="0.1 0.1 0.1" ambient="0.65 0.65 0.65"
directional="true" castshadow="false"/>
<geom type="plane" size="50 50 1" material="groundmat"/>

<!-- ===== Raised crop beds & plants (rotatable). ===== -->
<body name="rows" pos="0 0 0">
<joint name="rows_yaw" type="hinge" axis="0 0 1" limited="false"/>

<!-- Long rows (80 m) in multiple lanes. -->
<geom type="box" size="40 0.18 0.05" pos="0 0.80 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 -0.80 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 1.40 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 -1.40 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 2.00 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 -2.00 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 2.60 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 -2.60 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 3.20 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 -3.20 0.05" material="rowsoil"/>

<!-- Extra right-side rows (negative Y) to fill FOV. -->
<geom type="box" size="40 0.18 0.05" pos="0 -3.80 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 -4.40 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 -5.00 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 -5.60 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 -6.20 0.05" material="rowsoil"/>

<!-- Extra left/visible side rows (+Y). -->
<geom type="box" size="40 0.18 0.05" pos="0 3.80 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 4.40 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 5.00 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 5.60 0.05" material="rowsoil"/>
<geom type="box" size="40 0.18 0.05" pos="0 6.20 0.05" material="rowsoil"/>
</body>
</worldbody>

<!-- Actuators and Sensors defined in get_mujoco_xml(). -->
<actuator>
</actuator>

<sensor>
</sensor>
</mujoco>
52 changes: 52 additions & 0 deletions examples/mujoco/farm-ng/example_simulation.scenic
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
from amiga import Amiga, Plant
from scenic.simulators.mujoco.simulator import MujocoSimulator
from scenic.simulators.mujoco.model import Ground, Hill

from scenic.core.regions import RectangularRegion
from scenic.core.vectors import Vector

simulator MujocoSimulator(base_xml_file='amiga_base.xml', use_viewer=True)

# Creating region for spawning objects.
field_region = RectangularRegion(Vector(-20, -10), 0, 40, 20)

# Creating irregular terrain (two hills).
hill1 = new Hill at (10, 10, 0), with height 2, with spread 0.3
hill2 = new Hill at (-10, -10, 0), with height 1.5, with spread 0.4

new Ground at (0, 0, 0),
with width 50,
with length 50,
with gridSize 50,
with terrain (hill1, hill2)

# Defining regions for the crop rows to ensure that they're parallel.
row_y_positions = [-6, -3, 0, 3, 6]

# Spawning multiple Amiga objects at different positions.
amiga1 = new Amiga at (8, 1, 0.5),
facing 0 deg

amiga2 = new Amiga at (-10, 2, 0.5),
facing 0 deg

# Creating plants along the crop rows.
# Row 1 (y = -6)
for i in range(-8, 6, 2):
new Plant at (i, -6, 0.1), with plant_type "corn"

# Row 2 (y = -3)
for j in range(-8, 6, 2):
new Plant at (j, -3, 0.1), with plant_type "wheat"

# # Row 3 (y = 0)
for k in range(-8, 6, 2):
new Plant at (k, 0, 0.1), with plant_type "soybean"

# # Row 4 (y = 3)
for l in range(-8, 6, 2):
new Plant at (l, 3, 0.1), with plant_type "lettuce"

# Row 5 (y = 6)
for m in range(-8, 6, 2):
new Plant at (m, 6, 0.1), with plant_type "tomato"
Loading