Skip to content

Commit e9f8a63

Browse files
committed
fix: mypy errors
1 parent 75b169f commit e9f8a63

1 file changed

Lines changed: 10 additions & 10 deletions

File tree

python/rcs/ompl/mj_ompl.py

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ def get_collision_bodies(xml_file, robot_name):
4040
for g in collision_bodies:
4141
name = g.get("name")
4242
if name is None:
43-
error_msg = f"Body {ET.tostring(g).rstrip()}'s name is None. Please give it a name in the XML file."
43+
error_msg = f"Body {ET.tostring(g).rstrip()!r}'s name is None. Please give it a name in the XML file."
4444
raise ValueError(error_msg)
4545
names.append(name)
4646

@@ -125,8 +125,8 @@ def __init__(
125125
for name in self.actuator_names
126126
if mj.mj_name2id(self.model, mj.mjtObj.mjOBJ_ACTUATOR, name) > -1
127127
]
128-
self.obstacle_body_ids = set()
129-
self.obstacle_geom_ids = set()
128+
self.obstacle_body_ids: set[int] = set()
129+
self.obstacle_geom_ids: set[int] = set()
130130
self._add_obstacle_body_ids(obstacle_body_names)
131131
self._add_obstacle_geom_ids(obstacle_geom_names)
132132

@@ -155,7 +155,7 @@ def _remove_obstacle_body_ids(self, obstacle_body_names: list | str):
155155
error_msg = f"_remove_obstacle_body_ids: obstacle body name {name} does not exist in the set."
156156
raise RuntimeError(error_msg)
157157

158-
def _add_obstacle_body_ids(self, obstacle_body_names: list | str):
158+
def _add_obstacle_body_ids(self, obstacle_body_names: list | None):
159159
"""
160160
Add specified obstacle bodies to the robot's obstacle checks, given their names.
161161
@@ -173,7 +173,7 @@ def _add_obstacle_body_ids(self, obstacle_body_names: list | str):
173173
error_msg = f"_add_obstacle_body_ids: obstacle body name {name} does not exist in the model."
174174
raise RuntimeError(error_msg)
175175

176-
def _add_obstacle_geom_ids(self, obstacle_geom_names: list | str):
176+
def _add_obstacle_geom_ids(self, obstacle_geom_names: list | None):
177177
"""
178178
Add specified obstacle geoms to the robot's obstacle checks, given their names.
179179
@@ -281,7 +281,7 @@ def ik(self, pose, q0=None, tcp_offset=None):
281281
numpy.ndarray: Joint positions that achieve the desired pose, or None if no solution is found.
282282
"""
283283
tcp_offset = tcp_offset if tcp_offset is not None else self.franka_hand_tcp
284-
return self.env.unwrapped.robot.get_ik().ik(pose, q0, tcp_offset)
284+
return self.env.unwrapped.robot.get_ik().ik(pose, q0, tcp_offset) # type: ignore[attr-defined]
285285

286286

287287
class MjOStateSpace(ob.RealVectorStateSpace):
@@ -423,7 +423,7 @@ def set_planner(self, planner_name):
423423

424424
self.ss.setPlanner(self.planner)
425425

426-
def plan(self, goal: np.ndarray, start: np.ndarray = None, allowed_time: float = DEFAULT_PLANNING_TIME):
426+
def plan(self, goal: np.ndarray, start: np.ndarray | None = None, allowed_time: float = DEFAULT_PLANNING_TIME):
427427
"""
428428
Plan a path to goal from current robot state.
429429
Can be combined with `ik_pose` to plan a path to a desired pose.
@@ -485,7 +485,7 @@ def _plan_start_goal(self, start: np.ndarray, goal: np.ndarray, allowed_time=DEF
485485
sol_path_list = [np.array(sol_path, dtype=np.float32) for sol_path in sol_path_list]
486486
return res, sol_path_list
487487

488-
def ik(self, pose: Pose, q0: np.ndarray = None, tcp_offset: Pose = None):
488+
def ik(self, pose: Pose, q0: np.ndarray | None = None, tcp_offset: Pose | None = None):
489489
"""
490490
Perform inverse kinematics to find joint positions that achieve the desired pose.
491491
@@ -516,7 +516,7 @@ def state_to_list(self, state):
516516
def set_state_sampler(self, state_sampler):
517517
self.space.set_state_sampler(state_sampler)
518518

519-
def add_collision_bodies(self, obstacle_body_names: list | str):
519+
def add_collision_bodies(self, obstacle_body_names: list):
520520
"""
521521
Add specified obstacle bodies to the robot's obstacle checks.
522522
Prints a warning if the body name does not exist in the model.
@@ -526,7 +526,7 @@ def add_collision_bodies(self, obstacle_body_names: list | str):
526526
"""
527527
self.robot._add_obstacle_body_ids(obstacle_body_names)
528528

529-
def add_collision_geoms(self, obstacle_geom_names: list | str):
529+
def add_collision_geoms(self, obstacle_geom_names: list):
530530
"""
531531
Add specified obstacle geometries to the robot's obstacle checks.
532532
Prints a warning if the geometry name does not exist in the model.

0 commit comments

Comments
 (0)