Skip to content
Merged
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
5 changes: 2 additions & 3 deletions commands/basic_commands.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
import logging
import numpy as np
import PAROL6_ROBOT
from .ik_helpers import CommandValue

logger = logging.getLogger(__name__)

Expand Down Expand Up @@ -121,7 +120,7 @@ def __init__(self, joint, speed_percentage=None, duration=None, distance_deg=Non

def prepare_for_execution(self, current_position_in):
"""Pre-computes speeds and target positions using live data."""
logger.debug(f" -> Preparing for Jog command...")
logger.debug(" -> Preparing for Jog command...")

# Joint direction and index mapping
self.direction = 1 if 0 <= self.joint <= 5 else -1
Expand Down Expand Up @@ -261,7 +260,7 @@ def __init__(self, joints, speed_percentages, duration):

def prepare_for_execution(self, current_position_in):
"""Pre-computes the speeds for each joint."""
logger.debug(f" -> Preparing for MultiJog command...")
logger.debug(" -> Preparing for MultiJog command...")

for i, joint in enumerate(self.joints):
# Index mapping: 0-5 positive, 6-11 negative direction
Expand Down
6 changes: 3 additions & 3 deletions commands/gripper_commands.py
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ def execute_step(self, Position_in, Homed_in, Speed_out, Command_out,
# Check for completion
current_position = Gripper_data_in[1]
if abs(current_position - self.target_position) <= 5:
logger.info(f" -> Gripper move complete.")
logger.info(" -> Gripper move complete.")
self.is_finished = True
# Set command back to idle
bitfield = [1, 0, not InOut_in[4], 1, 0, 0, 0, 0]
Expand All @@ -136,12 +136,12 @@ def execute_step(self, Position_in, Homed_in, Speed_out, Command_out,
return True

if (object_detection == 1) and (self.target_position > current_position):
logger.info(f" -> Gripper move holding position due to object detection when closing.")
logger.info(" -> Gripper move holding position due to object detection when closing.")
self.is_finished = True
return True

if (object_detection == 2) and (self.target_position < current_position):
logger.info(f" -> Gripper move holding position due to object detection when opening.")
logger.info(" -> Gripper move holding position due to object detection when opening.")
self.is_finished = True
return True

Expand Down
1 change: 0 additions & 1 deletion commands/ik_helpers.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@
import numpy as np
import logging
from collections import namedtuple
from typing import Optional
from roboticstoolbox import DHRobot
from spatialmath import SE3
from spatialmath.base import trinterp
Expand Down
2 changes: 1 addition & 1 deletion commands/joint_commands.py
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ def prepare_for_execution(self, current_position_in):

except Exception as e:
logger.error(f" -> VALIDATION FAILED: Could not calculate velocity-based trajectory. Error: {e}")
logger.info(f" -> Please check Joint_min/max_speed and Joint_min/max_acc values in PAROL6_ROBOT.py.")
logger.info(" -> Please check Joint_min/max_speed and Joint_min/max_acc values in PAROL6_ROBOT.py.")
self.is_valid = False
return

Expand Down
18 changes: 7 additions & 11 deletions commands/smooth_commands.py
Original file line number Diff line number Diff line change
Expand Up @@ -8,16 +8,13 @@
import PAROL6_ROBOT
from spatialmath import SE3
from smooth_motion import (
CircularMotion, SplineMotion, MotionBlender,
HelixMotion, AdvancedMotionBlender, WaypointTrajectoryPlanner
CircularMotion, SplineMotion, HelixMotion, WaypointTrajectoryPlanner
)
from .ik_helpers import solve_ik_with_adaptive_tol_subdivision
from .cartesian_commands import MovePoseCommand

logger = logging.getLogger(__name__)

# Import MovePoseCommand for transition commands
from .cartesian_commands import MovePoseCommand

def transform_command_params_to_wrf(command_type: str, params: dict, frame: str, current_position_in) -> dict:
"""
Transform command parameters from TRF to WRF.
Expand Down Expand Up @@ -313,7 +310,7 @@ def prepare_for_execution(self, current_position_in):
if self.transition_command:
self.transition_command.prepare_for_execution(current_position_in)
if not self.transition_command.is_valid:
logger.error(f" -> ERROR: Cannot reach specified start position")
logger.error(" -> ERROR: Cannot reach specified start position")
self.is_valid = False
self.error_state = True
self.error_message = "Cannot reach specified start position"
Expand Down Expand Up @@ -342,7 +339,7 @@ def execute_step(self, Position_in, Homed_in, Speed_out, Command_out, **kwargs):
)

if is_done:
logger.info(f" -> Transition complete")
logger.info(" -> Transition complete")
self.transition_complete = True
return False

Expand Down Expand Up @@ -370,7 +367,7 @@ def execute_step(self, Position_in, Homed_in, Speed_out, Command_out, **kwargs):
)

if not ik_result.success:
logger.error(f" -> ERROR: Cannot reach first trajectory point")
logger.error(" -> ERROR: Cannot reach first trajectory point")
self.is_finished = True
self.error_state = True
self.error_message = "Cannot reach trajectory start"
Expand Down Expand Up @@ -884,7 +881,7 @@ def prepare_for_execution(self, current_position_in):
def generate_main_trajectory(self, effective_start_pose):
"""Generate helix with entry trajectory if needed and proper trajectory profile."""
# Import here to avoid circular dependencies
from smooth_motion import HelixMotion, CircularMotion
from smooth_motion import CircularMotion
helix_gen = HelixMotion()

# Get helix axis (default Z for WRF, transformed for TRF)
Expand Down Expand Up @@ -1024,7 +1021,7 @@ def generate_main_trajectory(self, effective_start_pose):
else:
# Replace first waypoint with actual start to ensure continuity
modified_waypoints = [effective_start_pose] + self.waypoints[1:]
logger.info(f" Replaced first waypoint with actual start position")
logger.info(" Replaced first waypoint with actual start position")

timestamps = np.linspace(0, self.duration, len(modified_waypoints))

Expand Down Expand Up @@ -1291,7 +1288,6 @@ def prepare_for_execution(self, current_position_in):

def generate_main_trajectory(self, effective_start_pose):
"""Generate waypoint trajectory with corner cutting."""
from smooth_motion import WaypointTrajectoryPlanner

# Ensure first waypoint matches effective start pose
first_wp_error = np.linalg.norm(
Expand Down
2 changes: 1 addition & 1 deletion gcode/commands.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
"""

import numpy as np
from typing import Dict, List, Optional, Tuple
from typing import Dict, Optional
import sys
import os

Expand Down
3 changes: 1 addition & 2 deletions gcode/coordinates.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,7 @@

import json
import os
import numpy as np
from typing import Dict, List, Optional, Tuple
from typing import Dict, List, Optional


class WorkCoordinateSystem:
Expand Down
6 changes: 3 additions & 3 deletions gcode/interpreter.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,11 +7,11 @@

import os
import numpy as np
from typing import List, Dict, Optional, Union, Tuple
from .parser import GcodeParser, GcodeToken
from typing import List, Dict, Optional, Union
from .parser import GcodeParser
from .state import GcodeState
from .coordinates import WorkCoordinateSystem
from .commands import create_command_from_token, GcodeCommand
from .commands import create_command_from_token


class GcodeInterpreter:
Expand Down
4 changes: 2 additions & 2 deletions gcode/state.py
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@

import json
import os
from typing import Dict, Optional, Tuple
from dataclasses import dataclass, field, asdict
from typing import Dict, Optional
from dataclasses import dataclass, field


@dataclass
Expand Down
2 changes: 1 addition & 1 deletion gcode/utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

import math
import numpy as np
from typing import Dict, List, Tuple, Optional
from typing import Dict, List


def feed_rate_to_duration(distance: float, feed_rate: float) -> float:
Expand Down
25 changes: 25 additions & 0 deletions parol6/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
"""
PAROL6 Python Package

A unified library for controlling PAROL6 robot arms with async-first UDP client,
optional sync wrapper, and server management capabilities.

Key components:
- AsyncRobotClient: Async UDP client for robot operations
- RobotClient: Sync wrapper with automatic event loop handling
- ServerManager: Manages headless controller process lifecycle
- ensure_server: Convenience function to auto-start controller when needed
"""

from ._version import __version__
from .client.async_client import AsyncRobotClient
from .client.sync_client import RobotClient
from .server.manager import ServerManager, ensure_server

__all__ = [
"__version__",
"AsyncRobotClient",
"RobotClient",
"ServerManager",
"ensure_server"
]
3 changes: 3 additions & 0 deletions parol6/_version.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
"""Version information for parol6 package."""

__version__ = "0.1.0"
1 change: 1 addition & 0 deletions parol6/cli/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
"""Command-line interface modules."""
16 changes: 16 additions & 0 deletions parol6/cli/server.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
"""
CLI entry point for parol6-server command.

This module provides the command-line interface for starting the PAROL6 headless controller.
"""

from parol6.server.headless_commander import main


def main_entry():
"""Entry point for the parol6-server command."""
main()


if __name__ == "__main__":
main_entry()
1 change: 1 addition & 0 deletions parol6/client/__init__.py
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
"""Client modules for robot communication."""
Loading