Skip to content

Commit

Permalink
lint
Browse files Browse the repository at this point in the history
  • Loading branch information
WT-MM committed Jan 15, 2025
1 parent 3a9d095 commit 99730f5
Show file tree
Hide file tree
Showing 3 changed files with 9 additions and 7 deletions.
8 changes: 4 additions & 4 deletions kos_sim/services.py
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@ def __init__(self, simulator: MujocoSimulator, step_controller: StepController)
self.simulator = simulator
self.step_controller = step_controller

def Reset( # noqa: N802
def Reset( # noqa: N802
self, request: sim_pb2.ResetRequest, context: grpc.ServicerContext
) -> common_pb2.ActionResponse: # noqa: N802
"""Reset the simulation to initial or specified state."""
Expand All @@ -38,7 +38,7 @@ def Reset( # noqa: N802
context.set_details(str(e))
return common_pb2.ActionResponse(success=False, error=str(e))

def SetPaused( # noqa: N802
def SetPaused( # noqa: N802
self, request: sim_pb2.SetPausedRequest, context: grpc.ServicerContext
) -> common_pb2.ActionResponse: # noqa: N802
"""Pause or unpause the simulation."""
Expand All @@ -52,7 +52,7 @@ def SetPaused( # noqa: N802
context.set_details(str(e))
return common_pb2.ActionResponse(success=False, error=str(e))

def Step( # noqa: N802
def Step( # noqa: N802
self, request: sim_pb2.StepRequest, context: grpc.ServicerContext
) -> common_pb2.ActionResponse: # noqa: N802
"""Step the simulation forward."""
Expand Down Expand Up @@ -102,7 +102,7 @@ def SetParameters( # noqa: N802
context.set_details(str(e))
return common_pb2.ActionResponse(success=False, error=str(e))

def GetParameters( # noqa: N802
def GetParameters( # noqa: N802
self, request: empty_pb2.Empty, context: grpc.ServicerContext
) -> sim_pb2.GetParametersResponse:
"""Get current simulation parameters."""
Expand Down
4 changes: 2 additions & 2 deletions kos_sim/test_client.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,8 @@ def test_sim_commands(host: str = "localhost", port: int = 50051) -> None:

# Test parameters
frequency = 1.0 # Hz
amplitude = 45.0 # degrees
duration = 5.0 # seconds
_amplitude = 45.0 # degrees
_duration = 5.0 # seconds

# Send command
sim.set_parameters(time_scale=frequency)
Expand Down
4 changes: 3 additions & 1 deletion kos_sim/test_viewer.py
Original file line number Diff line number Diff line change
@@ -1,7 +1,9 @@
"""Test script for the viewer."""

import mujoco
import mujoco_viewer

model = mujoco.MjModel.from_xml_path('models/gpr/robot_fixed.xml')
model = mujoco.MjModel.from_xml_path("models/gpr/robot_fixed.xml")
data = mujoco.MjData(model)

# create the viewer object
Expand Down

0 comments on commit 99730f5

Please sign in to comment.