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
2 changes: 1 addition & 1 deletion src/panda/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ ros2 launch panda panda_pick_and_place_cubes.launch.py
ros2 launch panda panda_pick_and_place_cubes.launch.py cube_count:=5

# Restricted corridor: narrow passage obstacle-avoidance demo
ros2 launch panda panda_restricted_corridor.launch.py
ros2 launch panda panda_multi_object_sequence.launch.py

# Restricted pillars: pillar field obstacle-avoidance demo
ros2 launch panda panda_restricted_pillars.launch.py
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,9 +16,19 @@ def generate_launch_description() -> LaunchDescription:
),
launch_arguments={
'world_file': PathJoinSubstitution(
[FindPackageShare('panda'), 'worlds', 'restricted_corridor_env.sdf']
[FindPackageShare('panda'), 'worlds', 'multi_object_sequential_env.sdf']
),
'bridge_external_camera': 'false',
# External RGB-D camera positioned in front of the robot and table,
# elevated and angled down so it sees the full workspace: all three
# target objects, the corridor walls/barriers, and the Panda arm.
'spawn_external_rgbd_camera': 'true',
'external_camera_x': '1.10',
'external_camera_y': '1.80',
'external_camera_z': '2.10',
'external_camera_roll': '0.0',
'external_camera_pitch': '0.70',
'external_camera_yaw': '3.14159',
}.items(),
)
]
Expand Down
61 changes: 61 additions & 0 deletions src/panda/launch/panda_vla_pipeline.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
from launch import LaunchDescription
from launch.actions import IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import PathJoinSubstitution
from launch_ros.substitutions import FindPackageShare


def generate_launch_description() -> LaunchDescription:
"""VLA sort-and-place environment.

Table layout (top-down, robot at x=0 y=1.70 facing +x):

obj_sphere (red ball) – (0.35, 1.72)
obj_puck (orange disc) – (0.45, 1.65)
obj_brick (green block) – (0.30, 1.90)
obj_cylinder(blue can) – (0.42, 1.88)

basket_red – (0.55, 1.62) ← place red objects here
basket_blue – (0.55, 1.80) ← place blue objects here
basket_green – (0.55, 1.98) ← place green objects here

External RGB-D camera: x=1.10, y=1.80, z=2.10, pitch=0.70, yaw=π
→ positioned directly in front of the arm+table, elevated and angled
down so it captures all objects, all baskets, and the Panda end-effector.

Wrist-eye camera: built into Panda URDF → /wrist_eye/image_raw
/wrist_eye/depth/image_raw
"""
return LaunchDescription(
[
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
PathJoinSubstitution(
[FindPackageShare('panda'), 'launch', 'panda_pick_and_place.launch.py']
)
),
launch_arguments={
'world_file': PathJoinSubstitution(
[FindPackageShare('panda'), 'worlds', 'vla_pipeline_env.sdf']
),
# Cube spawner disabled – objects are embedded in the world SDF.
'cube_count': '0',
# Wrist camera is always bridged by panda_pick_and_place.
# External in-world camera (rgbd_camera topic) is not used here.
'bridge_external_camera': 'false',
# Spawn a dedicated front-view RGB-D camera at run-time so
# its pose can be tuned without editing the world SDF.
'spawn_external_rgbd_camera': 'true',
# Camera sits in front of the robot and table, looking back
# at roughly 40° downward (pitch=0.70 rad) to see the full
# table surface including objects and baskets.
'external_camera_x': '1.10',
'external_camera_y': '1.80',
'external_camera_z': '2.10',
'external_camera_roll': '0.0',
'external_camera_pitch': '0.70',
'external_camera_yaw': '3.14159',
}.items(),
)
]
)
303 changes: 303 additions & 0 deletions src/panda/worlds/multi_object_sequential_env.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,303 @@
<?xml version='1.0'?>
<sdf version='1.9'>
<world name='multi_object_sequential_env'>
<physics name='1ms' type='ignored'>
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
<real_time_update_rate>1000</real_time_update_rate>
</physics>

<plugin name='gz::sim::systems::Physics' filename='gz-sim-physics-system'/>
<plugin name='gz::sim::systems::UserCommands' filename='gz-sim-user-commands-system'/>
<plugin name='gz::sim::systems::Sensors' filename='gz-sim-sensors-system'>
<render_engine>ogre2</render_engine>
</plugin>
<plugin name='gz::sim::systems::SceneBroadcaster' filename='gz-sim-scene-broadcaster-system'/>

<scene>
<ambient>0.45 0.45 0.45 1</ambient>
<background>0.70 0.72 0.74 1</background>
<shadows>true</shadows>
</scene>

<gravity>0 0 -9.8</gravity>

<include>
<uri>model://ground_plane</uri>
</include>

<include>
<uri>model://sun</uri>
</include>

<include>
<uri>model://table</uri>
<pose>0.270759 1.801050 0 0 0 0</pose>
</include>

<!--
Layout overview (top-down, robot at origin facing +x):

y=1.60 ─────────────────────── Left wall ────────────────────────── y=1.60
[OBJ1] [ gap ] [OBJ2] [ gap ] [OBJ3] [ gap ]
[barrier_a] [barrier_b] [barrier_c]
y=2.00 ─────────────────────── Right wall ───────────────────────── y=2.00
x≈0.26 x=0.37 x≈0.44 x=0.52 x≈0.60 x=0.68

Each blue barrier is two segments with a central gap (~0.14 m) through
which the arm can reach the next zone. Corridor is wider (0.40 m) for
more arm clearance around the side walls.

Objects:
1. Cube (green) – Zone 1, slightly left of centre
2. Cylinder (blue) – Zone 2, centred between side walls
3. Rod/prism (orange) – Zone 3, centred, close to barrier C
-->

<!-- ── Side walls (wider corridor: y=1.60 / y=2.00) ── -->
<model name='corridor_wall_left'>
<static>true</static>
<pose>0.44 1.60 1.085 0 0 0</pose>
<link name='link'>
<collision name='collision'>
<geometry>
<box><size>0.48 0.03 0.14</size></box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box><size>0.48 0.03 0.14</size></box>
</geometry>
<material>
<ambient>1 1 0 1</ambient>
<diffuse>1 1 0 1</diffuse>
</material>
</visual>
</link>
</model>

<model name='corridor_wall_right'>
<static>true</static>
<pose>0.44 2.00 1.085 0 0 0</pose>
<link name='link'>
<collision name='collision'>
<geometry>
<box><size>0.48 0.03 0.14</size></box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box><size>0.48 0.03 0.14</size></box>
</geometry>
<material>
<ambient>1 1 0 1</ambient>
<diffuse>1 1 0 1</diffuse>
</material>
</visual>
</link>
</model>

<!-- ── Barrier A (x=0.37): two segments, central gap y=1.73→1.87 ── -->
<model name='barrier_a_left'>
<static>true</static>
<!-- covers y=1.60→1.73, centre=(1.60+1.73)/2=1.665, size_y=0.13 -->
<pose>0.37 1.665 1.085 0 0 0</pose>
<link name='link'>
<collision name='collision'>
<geometry>
<box><size>0.03 0.13 0.14</size></box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box><size>0.03 0.13 0.14</size></box>
</geometry>
<material>
<ambient>1 1 0 1</ambient>
<diffuse>1 1 0 1</diffuse>
</material>
</visual>
</link>
</model>

<model name='barrier_a_right'>
<static>true</static>
<!-- covers y=1.87→2.00, centre=(1.87+2.00)/2=1.935, size_y=0.13 -->
<pose>0.37 1.935 1.085 0 0 0</pose>
<link name='link'>
<collision name='collision'>
<geometry>
<box><size>0.03 0.13 0.14</size></box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box><size>0.03 0.13 0.14</size></box>
</geometry>
<material>
<ambient>1 1 0 1</ambient>
<diffuse>1 1 0 1</diffuse>
</material>
</visual>
</link>
</model>

<!-- ── Barrier B (x=0.52): two segments, central gap y=1.73→1.87 ── -->
<model name='barrier_b_left'>
<static>true</static>
<pose>0.52 1.665 1.085 0 0 0</pose>
<link name='link'>
<collision name='collision'>
<geometry>
<box><size>0.03 0.13 0.14</size></box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box><size>0.03 0.13 0.14</size></box>
</geometry>
<material>
<ambient>1 1 0 1</ambient>
<diffuse>1 1 0 1</diffuse>
</material>
</visual>
</link>
</model>

<model name='barrier_b_right'>
<static>true</static>
<pose>0.52 1.935 1.085 0 0 0</pose>
<link name='link'>
<collision name='collision'>
<geometry>
<box><size>0.03 0.13 0.14</size></box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box><size>0.03 0.13 0.14</size></box>
</geometry>
<material>
<ambient>1 1 0 1</ambient>
<diffuse>1 1 0 1</diffuse>
</material>
</visual>
</link>
</model>

<!-- ── Barrier C (x=0.68): full-width end wall ── -->
<model name='barrier_c'>
<static>true</static>
<pose>0.68 1.800 1.085 0 0 0</pose>
<link name='link'>
<collision name='collision'>
<geometry>
<box><size>0.03 0.40 0.14</size></box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box><size>0.03 0.40 0.14</size></box>
</geometry>
<material>
<ambient>1 1 0 1</ambient>
<diffuse>1 1 0 1</diffuse>
</material>
</visual>
</link>
</model>

<!-- ── Object 1: Cube (green) – Zone 1, slightly left of centre ── -->
<!-- <model name='target_cube'>
<static>false</static>
<pose>0.26 1.73 1.040 0 0 0</pose>
<link name='link'>
<inertial>
<mass>0.12</mass>
<inertia>
<ixx>0.00005</ixx><ixy>0.0</ixy><ixz>0.0</ixz>
<iyy>0.00005</iyy><iyz>0.0</iyz>
<izz>0.00005</izz>
</inertia>
</inertial>
<collision name='collision'>
<geometry>
<box><size>0.05 0.05 0.05</size></box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box><size>0.05 0.05 0.05</size></box>
</geometry>
<material>
<ambient>0 1 0 1</ambient>
<diffuse>0 1 0 1</diffuse>
<specular>0.05 0.05 0.05 1</specular>
</material>
</visual>
</link>
</model> -->

<!-- ── Object 2: Cylinder (red) – Zone 2, centred ── -->
<model name='target_cylinder'>
<static>false</static>
<pose>0.44 1.80 1.040 0 0 0</pose>
<link name='link'>
<inertial>
<mass>0.12</mass>
<inertia>
<ixx>0.00005</ixx><ixy>0.0</ixy><ixz>0.0</ixz>
<iyy>0.00005</iyy><iyz>0.0</iyz>
<izz>0.00004</izz>
</inertia>
</inertial>
<collision name='collision'>
<geometry>
<cylinder><radius>0.025</radius><length>0.05</length></cylinder>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<cylinder><radius>0.025</radius><length>0.05</length></cylinder>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>0.05 0.05 0.05 1</specular>
</material>
</visual>
</link>
</model>

<!-- ── Object 3: cuboid (blue) – Zone 3, centred, close to barrier C ── -->
<model name='target_cuboid'>
<static>false</static>
<pose>0.60 1.80 1.040 0 0 0</pose>
<link name='link'>
<inertial>
<mass>0.12</mass>
<inertia>
<ixx>0.00003</ixx><ixy>0.0</ixy><ixz>0.0</ixz>
<iyy>0.00008</iyy><iyz>0.0</iyz>
<izz>0.00008</izz>
</inertia>
</inertial>
<collision name='collision'>
<geometry>
<box><size>0.08 0.04 0.04</size></box>
</geometry>
</collision>
<visual name='visual'>
<geometry>
<box><size>0.08 0.04 0.04</size></box>
</geometry>
<material>
<ambient>0 0 1 1</ambient>
<diffuse>0 0 1 1</diffuse>
<specular>0.05 0.05 0.05 1</specular>
</material>
</visual>
</link>
</model>
</world>
</sdf>
Loading