Spaces:
Sleeping
Sleeping
Commit ·
7d676ca
1
Parent(s): 43d93f2
Melhorar espiral: aumentar raio (0.05-0.20) e usar 1.5 rotacoes (3*pi) para melhor visibilidade
Browse files- cliport/generated_tasks/build_spiral_fixed.py +8 -6
- prompts/topdown_task_generation_prompt/cliport_prompt_code_split_template.txt +2 -2
- prompts/topdown_task_generation_prompt_simple/cliport_prompt_code_split_template.txt +2 -2
- prompts/vanilla_task_generation_prompt/cliport_prompt_code_split_template.txt +2 -2
cliport/generated_tasks/build_spiral_fixed.py
CHANGED
|
@@ -37,19 +37,21 @@ class BuildSpiralWithColoredBlocks(Task):
|
|
| 37 |
objs.append(block_id)
|
| 38 |
|
| 39 |
# Define spiral placement using polar coordinates with increasing radius
|
| 40 |
-
# Spiral: radius increases, angle increases (
|
| 41 |
num_blocks = 6
|
| 42 |
spiral_center = (0.5, 0.0, 0.02) # Center of workspace, fixed pose
|
| 43 |
base_rotation = (0, 0, 0, 1)
|
| 44 |
base_pose = (spiral_center, base_rotation)
|
| 45 |
|
| 46 |
-
# Spiral parameters:
|
|
|
|
|
|
|
| 47 |
spiral_place_pos = []
|
| 48 |
for i in range(num_blocks):
|
| 49 |
-
# Angle increases from 0 to
|
| 50 |
-
angle = (i / num_blocks) *
|
| 51 |
-
# Radius increases linearly from 0.
|
| 52 |
-
radius = 0.
|
| 53 |
# Convert to Cartesian coordinates relative to center
|
| 54 |
x = radius * np.cos(angle)
|
| 55 |
y = radius * np.sin(angle)
|
|
|
|
| 37 |
objs.append(block_id)
|
| 38 |
|
| 39 |
# Define spiral placement using polar coordinates with increasing radius
|
| 40 |
+
# Spiral: radius increases, angle increases (1.5 full rotations = 3*pi for better visibility)
|
| 41 |
num_blocks = 6
|
| 42 |
spiral_center = (0.5, 0.0, 0.02) # Center of workspace, fixed pose
|
| 43 |
base_rotation = (0, 0, 0, 1)
|
| 44 |
base_pose = (spiral_center, base_rotation)
|
| 45 |
|
| 46 |
+
# Spiral parameters:
|
| 47 |
+
# - Radius increases from 0.05 to 0.20 (larger range for better visibility)
|
| 48 |
+
# - Angle goes from 0 to 3*pi (1.5 full rotations for clearer spiral pattern)
|
| 49 |
spiral_place_pos = []
|
| 50 |
for i in range(num_blocks):
|
| 51 |
+
# Angle increases from 0 to 3*pi (1.5 full rotations)
|
| 52 |
+
angle = (i / (num_blocks - 1)) * 3 * np.pi if num_blocks > 1 else 0
|
| 53 |
+
# Radius increases linearly from 0.05 to 0.20 (larger spacing)
|
| 54 |
+
radius = 0.05 + (i / (num_blocks - 1)) * 0.15 if num_blocks > 1 else 0.05
|
| 55 |
# Convert to Cartesian coordinates relative to center
|
| 56 |
x = radius * np.cos(angle)
|
| 57 |
y = radius * np.sin(angle)
|
prompts/topdown_task_generation_prompt/cliport_prompt_code_split_template.txt
CHANGED
|
@@ -282,11 +282,11 @@ CRITICAL FOR PYRAMIDS, BRIDGES, AND MULTI-LAYER STRUCTURES:
|
|
| 282 |
CRITICAL FOR SPIRAL PATTERNS:
|
| 283 |
- For spiral patterns, you MUST use POLAR COORDINATES with increasing radius and varying angle
|
| 284 |
- DO NOT use rectangular patterns like `[(0, 0), (0.04, 0), (0.04, 0.04), ...]` - that creates a rectangle, NOT a spiral
|
| 285 |
-
- Use: `angle = (i / num_blocks) *
|
| 286 |
- Convert to Cartesian: `x = radius * np.cos(angle)`, `y = radius * np.sin(angle)`
|
| 287 |
- Use a FIXED center pose (e.g., `(0.5, 0.0, 0.02)`) within workspace bounds, NOT `get_random_pose()`
|
| 288 |
- Apply the center pose using `utils.apply()`: `targs = [(utils.apply(base_pose, (x, y, z)), base_pose[1]) for x, y, z in spiral_positions]`
|
| 289 |
-
-
|
| 290 |
|
| 291 |
CRITICAL FOR MULTIPLE STRUCTURES (e.g., "two pyramids", "three towers", "multiple zones", "pyramid and row"):
|
| 292 |
- If the task requires MULTIPLE separate structures (e.g., "two pyramids", "one blue pyramid and one red pyramid", "pyramid and row"), you MUST create separate base poses for each structure
|
|
|
|
| 282 |
CRITICAL FOR SPIRAL PATTERNS:
|
| 283 |
- For spiral patterns, you MUST use POLAR COORDINATES with increasing radius and varying angle
|
| 284 |
- DO NOT use rectangular patterns like `[(0, 0), (0.04, 0), (0.04, 0.04), ...]` - that creates a rectangle, NOT a spiral
|
| 285 |
+
- Use: `angle = (i / (num_blocks - 1)) * 3 * np.pi` (1.5 full rotations for better visibility) and `radius = 0.05 + (i / (num_blocks - 1)) * 0.15` (radius from 0.05 to 0.20)
|
| 286 |
- Convert to Cartesian: `x = radius * np.cos(angle)`, `y = radius * np.sin(angle)`
|
| 287 |
- Use a FIXED center pose (e.g., `(0.5, 0.0, 0.02)`) within workspace bounds, NOT `get_random_pose()`
|
| 288 |
- Apply the center pose using `utils.apply()`: `targs = [(utils.apply(base_pose, (x, y, z)), base_pose[1]) for x, y, z in spiral_positions]`
|
| 289 |
+
- IMPORTANT: Use larger radius range (0.05 to 0.20) and more rotations (1.5 turns = 3*pi) to make the spiral pattern clearly visible
|
| 290 |
|
| 291 |
CRITICAL FOR MULTIPLE STRUCTURES (e.g., "two pyramids", "three towers", "multiple zones", "pyramid and row"):
|
| 292 |
- If the task requires MULTIPLE separate structures (e.g., "two pyramids", "one blue pyramid and one red pyramid", "pyramid and row"), you MUST create separate base poses for each structure
|
prompts/topdown_task_generation_prompt_simple/cliport_prompt_code_split_template.txt
CHANGED
|
@@ -280,11 +280,11 @@ CRITICAL FOR PYRAMIDS, BRIDGES, AND MULTI-LAYER STRUCTURES:
|
|
| 280 |
CRITICAL FOR SPIRAL PATTERNS:
|
| 281 |
- For spiral patterns, you MUST use POLAR COORDINATES with increasing radius and varying angle
|
| 282 |
- DO NOT use rectangular patterns like `[(0, 0), (0.04, 0), (0.04, 0.04), ...]` - that creates a rectangle, NOT a spiral
|
| 283 |
-
- Use: `angle = (i / num_blocks) *
|
| 284 |
- Convert to Cartesian: `x = radius * np.cos(angle)`, `y = radius * np.sin(angle)`
|
| 285 |
- Use a FIXED center pose (e.g., `(0.5, 0.0, 0.02)`) within workspace bounds, NOT `get_random_pose()`
|
| 286 |
- Apply the center pose using `utils.apply()`: `targs = [(utils.apply(base_pose, (x, y, z)), base_pose[1]) for x, y, z in spiral_positions]`
|
| 287 |
-
-
|
| 288 |
|
| 289 |
CRITICAL FOR MULTIPLE STRUCTURES (e.g., "two pyramids", "three towers", "multiple zones", "pyramid and row"):
|
| 290 |
- If the task requires MULTIPLE separate structures (e.g., "two pyramids", "one blue pyramid and one red pyramid", "pyramid and row"), you MUST create separate base poses for each structure
|
|
|
|
| 280 |
CRITICAL FOR SPIRAL PATTERNS:
|
| 281 |
- For spiral patterns, you MUST use POLAR COORDINATES with increasing radius and varying angle
|
| 282 |
- DO NOT use rectangular patterns like `[(0, 0), (0.04, 0), (0.04, 0.04), ...]` - that creates a rectangle, NOT a spiral
|
| 283 |
+
- Use: `angle = (i / (num_blocks - 1)) * 3 * np.pi` (1.5 full rotations for better visibility) and `radius = 0.05 + (i / (num_blocks - 1)) * 0.15` (radius from 0.05 to 0.20)
|
| 284 |
- Convert to Cartesian: `x = radius * np.cos(angle)`, `y = radius * np.sin(angle)`
|
| 285 |
- Use a FIXED center pose (e.g., `(0.5, 0.0, 0.02)`) within workspace bounds, NOT `get_random_pose()`
|
| 286 |
- Apply the center pose using `utils.apply()`: `targs = [(utils.apply(base_pose, (x, y, z)), base_pose[1]) for x, y, z in spiral_positions]`
|
| 287 |
+
- IMPORTANT: Use larger radius range (0.05 to 0.20) and more rotations (1.5 turns = 3*pi) to make the spiral pattern clearly visible
|
| 288 |
|
| 289 |
CRITICAL FOR MULTIPLE STRUCTURES (e.g., "two pyramids", "three towers", "multiple zones", "pyramid and row"):
|
| 290 |
- If the task requires MULTIPLE separate structures (e.g., "two pyramids", "one blue pyramid and one red pyramid", "pyramid and row"), you MUST create separate base poses for each structure
|
prompts/vanilla_task_generation_prompt/cliport_prompt_code_split_template.txt
CHANGED
|
@@ -270,11 +270,11 @@ CRITICAL FOR PYRAMIDS, BRIDGES, AND MULTI-LAYER STRUCTURES:
|
|
| 270 |
CRITICAL FOR SPIRAL PATTERNS:
|
| 271 |
- For spiral patterns, you MUST use POLAR COORDINATES with increasing radius and varying angle
|
| 272 |
- DO NOT use rectangular patterns like `[(0, 0), (0.04, 0), (0.04, 0.04), ...]` - that creates a rectangle, NOT a spiral
|
| 273 |
-
- Use: `angle = (i / num_blocks) *
|
| 274 |
- Convert to Cartesian: `x = radius * np.cos(angle)`, `y = radius * np.sin(angle)`
|
| 275 |
- Use a FIXED center pose (e.g., `(0.5, 0.0, 0.02)`) within workspace bounds, NOT `get_random_pose()`
|
| 276 |
- Apply the center pose using `utils.apply()`: `targs = [(utils.apply(base_pose, (x, y, z)), base_pose[1]) for x, y, z in spiral_positions]`
|
| 277 |
-
-
|
| 278 |
|
| 279 |
CRITICAL FOR MULTIPLE STRUCTURES (e.g., "two pyramids", "three towers", "multiple zones", "pyramid and row"):
|
| 280 |
- If the task requires MULTIPLE separate structures (e.g., "two pyramids", "one blue pyramid and one red pyramid", "pyramid and row"), you MUST create separate base poses for each structure
|
|
|
|
| 270 |
CRITICAL FOR SPIRAL PATTERNS:
|
| 271 |
- For spiral patterns, you MUST use POLAR COORDINATES with increasing radius and varying angle
|
| 272 |
- DO NOT use rectangular patterns like `[(0, 0), (0.04, 0), (0.04, 0.04), ...]` - that creates a rectangle, NOT a spiral
|
| 273 |
+
- Use: `angle = (i / (num_blocks - 1)) * 3 * np.pi` (1.5 full rotations for better visibility) and `radius = 0.05 + (i / (num_blocks - 1)) * 0.15` (radius from 0.05 to 0.20)
|
| 274 |
- Convert to Cartesian: `x = radius * np.cos(angle)`, `y = radius * np.sin(angle)`
|
| 275 |
- Use a FIXED center pose (e.g., `(0.5, 0.0, 0.02)`) within workspace bounds, NOT `get_random_pose()`
|
| 276 |
- Apply the center pose using `utils.apply()`: `targs = [(utils.apply(base_pose, (x, y, z)), base_pose[1]) for x, y, z in spiral_positions]`
|
| 277 |
+
- IMPORTANT: Use larger radius range (0.05 to 0.20) and more rotations (1.5 turns = 3*pi) to make the spiral pattern clearly visible
|
| 278 |
|
| 279 |
CRITICAL FOR MULTIPLE STRUCTURES (e.g., "two pyramids", "three towers", "multiple zones", "pyramid and row"):
|
| 280 |
- If the task requires MULTIPLE separate structures (e.g., "two pyramids", "one blue pyramid and one red pyramid", "pyramid and row"), you MUST create separate base poses for each structure
|