Skip to content

Commit

Permalink
fix mypy issues
Browse files Browse the repository at this point in the history
  • Loading branch information
Victorlouisdg committed Dec 5, 2024
1 parent f638398 commit 7b54824
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 10 deletions.
16 changes: 8 additions & 8 deletions airo_drake/building/mobile_platform.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

def add_mobile_platform(
robot_diagram_builder: RobotDiagramBuilder,
drive_positions: Tuple[Vector2DType] = (
drive_positions: Tuple[Vector2DType, Vector2DType, Vector2DType, Vector2DType] = (
np.array([1, -0.5]),
np.array([1, 0.5]),
np.array([-1, -0.5]),
Expand Down Expand Up @@ -62,7 +62,7 @@ def add_mobile_platform(
mobi_urdf_path = airo_models.get_urdf_path("kelo_robile")

drive_transforms = [
RigidTransform(p=[brick_size * p[0], brick_size * p[1], 0], rpy=RollPitchYaw([0, 0, 0]))
RigidTransform(p=[brick_size * p[0], brick_size * p[1], 0], rpy=RollPitchYaw([0, 0, 0])) # type: ignore
for p in drive_positions
]

Expand All @@ -80,15 +80,15 @@ def add_mobile_platform(
mobi_part_indices.append(brick_index)

battery_transform = RigidTransform(
p=[brick_size * battery_position[0], brick_size * battery_position[1], 0], rpy=RollPitchYaw([0, 0, 0])
p=[brick_size * battery_position[0], brick_size * battery_position[1], 0], rpy=RollPitchYaw([0, 0, 0]) # type: ignore
)
battery_index = parser.AddModels(airo_models.get_urdf_path("kelo_robile_battery"))[0]
battery_frame = plant.GetFrameByName("base_link", battery_index)
plant.WeldFrames(robot_root_frame, battery_frame, battery_transform)
mobi_part_indices.append(battery_index)

cpu_transform = RigidTransform(
p=[brick_size * cpu_position[0], brick_size * cpu_position[1], 0], rpy=RollPitchYaw([0, 0, 0])
p=[brick_size * cpu_position[0], brick_size * cpu_position[1], 0], rpy=RollPitchYaw([0, 0, 0]) # type: ignore
)
cpu_index = parser.AddModels(airo_models.get_urdf_path("kelo_robile_cpu"))[0]
cpu_frame = plant.GetFrameByName("base_link", cpu_index)
Expand All @@ -100,8 +100,8 @@ def add_mobile_platform(
side_height_half = 0.5 * side_height
side_length_half = 0.5 * side_length
side_transforms = [
RigidTransform(p=[front_brick_position - side_length_half, -brick_size, side_height_half]),
RigidTransform(p=[front_brick_position - side_length_half, brick_size, side_height_half]),
RigidTransform(p=[front_brick_position - side_length_half, -brick_size, side_height_half]), # type: ignore
RigidTransform(p=[front_brick_position - side_length_half, brick_size, side_height_half]), # type: ignore
]

for side_transform in side_transforms:
Expand All @@ -114,7 +114,7 @@ def add_mobile_platform(
roof_length = side_length
roof_length_half = 0.5 * roof_length
roof_thickness_half = 0.5 * roof_thickness
roof_transform = RigidTransform(p=[front_brick_position - roof_length_half, 0, side_height + roof_thickness_half])
roof_transform = RigidTransform(p=[front_brick_position - roof_length_half, 0, side_height + roof_thickness_half]) # type: ignore

roof_urdf_path = airo_models.box_urdf_path([roof_length, roof_width, 0.03], "roof")
roof_index = parser.AddModels(roof_urdf_path)[0]
Expand All @@ -127,7 +127,7 @@ def add_mobile_platform(

def attach_mobile_platform_to_world(
robot_diagram_builder: RobotDiagramBuilder, mobi_model_index: ModelInstanceIndex, static_platform: bool
):
) -> None:
"""Attach the mobile platform to the world frame with a planar joint. This allows the mobile platform to
move around by setting the (x, y, theta) values of the joint.
Expand Down
4 changes: 2 additions & 2 deletions airo_drake/time_parametrization/toppra.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,9 +50,9 @@ def time_parametrize_toppra_mobile_platform(
if time_parametrization is None:
raise ValueError("TOPP-RA failed to find a valid time parametrization.")

pose_trajectory = PathParameterizedTrajectory(pose_trajectory, time_parametrization)
pose_trajectory_ = PathParameterizedTrajectory(pose_trajectory, time_parametrization)

return pose_trajectory
return pose_trajectory_


def time_parametrize_toppra(
Expand Down

0 comments on commit 7b54824

Please sign in to comment.