Skip to content

Commit a9cfcb9

Browse files
style(pre-commit): autofix
1 parent 3333587 commit a9cfcb9

File tree

2 files changed

+8
-4
lines changed

2 files changed

+8
-4
lines changed

simulator/carla_autoware/config/objects.json

+1-1
Original file line numberDiff line numberDiff line change
@@ -59,4 +59,4 @@
5959
}
6060
}
6161
]
62-
}
62+
}

simulator/carla_autoware/src/carla_autoware/carla_ros.py

+7-3
Original file line numberDiff line numberDiff line change
@@ -378,11 +378,15 @@ def imu(self, carla_imu_measurement):
378378
def control_callback(self, in_cmd):
379379
"""Convert and publish CARLA Ego Vehicle Control to AUTOWARE."""
380380
out_cmd = carla.VehicleAckermannControl(
381-
steer=numpy.clip(-math.degrees(in_cmd.lateral.steering_tire_angle)/self.max_steering_angle, -1.0, 1.0),
381+
steer=numpy.clip(
382+
-math.degrees(in_cmd.lateral.steering_tire_angle) / self.max_steering_angle,
383+
-1.0,
384+
1.0,
385+
),
382386
steer_speed=in_cmd.lateral.steering_tire_rotation_rate,
383387
speed=in_cmd.longitudinal.speed,
384388
acceleration=in_cmd.longitudinal.acceleration,
385-
jerk=in_cmd.longitudinal.jerk
389+
jerk=in_cmd.longitudinal.jerk,
386390
)
387391
self.current_control = out_cmd
388392

@@ -414,7 +418,7 @@ def ego_status(self):
414418
out_steering_state.steering_tire_angle = -math.radians(
415419
ego_vehicle.get_wheel_steer_angle(carla.VehicleWheelLocation.FL_Wheel)
416420
)
417-
421+
418422
out_gear_state.stamp = out_vel_state.header.stamp
419423
out_gear_state.report = GearReport.DRIVE
420424

0 commit comments

Comments
 (0)