Skip to content

Commit ffebe4f

Browse files
fred-labsfpasch
authored andcommitted
Code formatting
1 parent 846a811 commit ffebe4f

File tree

10 files changed

+55
-44
lines changed

10 files changed

+55
-44
lines changed

carla_ad_agent/CMakeLists.txt

+1-1
Original file line numberDiff line numberDiff line change
@@ -25,7 +25,7 @@ if(${ROS_VERSION} EQUAL 1)
2525
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch)
2626

2727
elseif(${ROS_VERSION} EQUAL 2)
28-
#TODO: remove
28+
# TODO: remove
2929
find_package(ament_cmake REQUIRED)
3030
find_package(rclpy REQUIRED)
3131
ament_export_dependencies(rclpy)

carla_common/src/carla_common/transforms.py

+8-5
Original file line numberDiff line numberDiff line change
@@ -326,21 +326,24 @@ def ros_pose_to_carla_transform(ros_pose):
326326
ros_point_to_carla_location(ros_pose.position),
327327
ros_quaternion_to_carla_rotation(ros_pose.orientation))
328328

329+
329330
def transform_matrix_to_ros_pose(mat):
330331
"""
331332
Convert a transform matrix to a ROS pose.
332333
"""
333-
quat = mat2quat(mat[:3,:3])
334+
quat = mat2quat(mat[:3, :3])
334335
msg = Pose()
335-
msg.position=Point(x=mat[0, 3], y=mat[1, 3], z=mat[2, 3])
336-
msg.orientation=Quaternion(w=quat[0], x=quat[1], y=quat[2], z=quat[3])
336+
msg.position = Point(x=mat[0, 3], y=mat[1, 3], z=mat[2, 3])
337+
msg.orientation = Quaternion(w=quat[0], x=quat[1], y=quat[2], z=quat[3])
337338
return msg
338339

340+
339341
def ros_pose_to_transform_matrix(msg):
340342
"""
341343
Convert a ROS pose to a transform matrix
342344
"""
343345
mat44 = numpy.eye(4)
344-
mat44[:3,:3] = quat2mat([msg.orientation.w, msg.orientation.x, msg.orientation.y, msg.orientation.z])
346+
mat44[:3, :3] = quat2mat([msg.orientation.w, msg.orientation.x,
347+
msg.orientation.y, msg.orientation.z])
345348
mat44[0:3, -1] = [msg.position.x, msg.position.y, msg.position.z]
346-
return mat44
349+
return mat44

carla_manual_control/src/carla_manual_control/carla_manual_control.py

+10-9
Original file line numberDiff line numberDiff line change
@@ -175,7 +175,7 @@ def render(self, game_clock, display):
175175
"""
176176
render the current image
177177
"""
178-
178+
179179
do_quit = self.controller.parse_events(game_clock)
180180
if do_quit:
181181
return
@@ -214,24 +214,25 @@ def __init__(self, role_name, hud, node):
214214

215215
self.vehicle_control_manual_override_publisher = \
216216
self.node.new_publisher(Bool,
217-
"/carla/{}/vehicle_control_manual_override".format(self.role_name),
218-
qos_profile=fast_latched_qos, callback_group=self.callback_group)
217+
"/carla/{}/vehicle_control_manual_override".format(
218+
self.role_name),
219+
qos_profile=fast_latched_qos, callback_group=self.callback_group)
219220

220221
self.vehicle_control_manual_override = False
221222

222223
self.auto_pilot_enable_publisher = \
223224
self.node.new_publisher(Bool,
224-
"/carla/{}/enable_autopilot".format(self.role_name),
225-
qos_profile=fast_qos, callback_group=self.callback_group)
225+
"/carla/{}/enable_autopilot".format(self.role_name),
226+
qos_profile=fast_qos, callback_group=self.callback_group)
226227

227228
self.vehicle_control_publisher = \
228229
self.node.new_publisher(CarlaEgoVehicleControl,
229-
"/carla/{}/vehicle_control_cmd_manual".format(self.role_name),
230-
qos_profile=fast_qos, callback_group=self.callback_group)
230+
"/carla/{}/vehicle_control_cmd_manual".format(self.role_name),
231+
qos_profile=fast_qos, callback_group=self.callback_group)
231232

232233
self.carla_status_subscriber = self.node.create_subscriber(CarlaStatus, "/carla/status",
233-
self._on_new_carla_frame,
234-
callback_group=self.callback_group)
234+
self._on_new_carla_frame,
235+
callback_group=self.callback_group)
235236

236237
self.set_autopilot(self._autopilot_enabled)
237238

carla_ros_bridge/src/carla_ros_bridge/actor_factory.py

+18-17
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212
from enum import Enum
1313

1414
try:
15-
import queue
15+
import queue
1616
except ImportError:
17-
import Queue as queue
18-
17+
import Queue as queue
18+
1919
from carla_ros_bridge.actor import Actor
2020
from carla_ros_bridge.spectator import Spectator
2121
from carla_ros_bridge.traffic import Traffic, TrafficLight
@@ -72,7 +72,7 @@ def __init__(self, node, world, sync_mode=False):
7272

7373
self._task_queue = queue.Queue()
7474
self._last_task = None
75-
self._known_actor_ids = [] # used to immediately reply to spawn_actor/destroy_actor calls
75+
self._known_actor_ids = [] # used to immediately reply to spawn_actor/destroy_actor calls
7676

7777
self.lock = Lock()
7878
self.spawn_lock = Lock()
@@ -128,15 +128,15 @@ def update_available_objects(self):
128128
task = self._task_queue.get()
129129
if task[0] == ActorFactory.TaskType.SPAWN_PSEUDO_ACTOR:
130130
pseudo_object = task[1]
131-
self._create_object(pseudo_object[0], pseudo_object[1].type, pseudo_object[1].id, pseudo_object[1].attach_to, pseudo_object[1].transform)
131+
self._create_object(pseudo_object[0], pseudo_object[1].type, pseudo_object[1].id,
132+
pseudo_object[1].attach_to, pseudo_object[1].transform)
132133
elif task[0] == ActorFactory.TaskType.DESTROY_ACTOR:
133134
actor_id = task[1]
134135
self._destroy_object(actor_id, delete_actor=True)
135136
elif task[0] == ActorFactory.TaskType.SYNC:
136137
break
137138
self.lock.release()
138139

139-
140140
def update_actor_states(self, frame_id, timestamp):
141141
"""
142142
update the state of all known actors
@@ -152,7 +152,7 @@ def update_actor_states(self, frame_id, timestamp):
152152

153153
def clear(self):
154154
for _, actor in self.actors.items():
155-
actor.destroy()
155+
actor.destroy()
156156
self.actors.clear()
157157

158158
def spawn_actor(self, req):
@@ -164,7 +164,7 @@ def spawn_actor(self, req):
164164
"""
165165
with self.spawn_lock:
166166
if "pseudo" in req.type:
167-
#only allow spawning pseudo objects if parent actor already exists in carla
167+
# only allow spawning pseudo objects if parent actor already exists in carla
168168
if req.attach_to != 0:
169169
carla_actor = self.world.get_actor(req.attach_to)
170170
if carla_actor is None:
@@ -189,7 +189,7 @@ def _destroy_actor(self, uid):
189189
if uid in self._known_actor_ids:
190190
objects_to_destroy.append(uid)
191191
self._known_actor_ids.remove(uid)
192-
192+
193193
# remove actors that have the actor to be removed as parent.
194194
for actor in list(self.actors.values()):
195195
if actor.parent is not None and actor.parent.uid == uid:
@@ -225,7 +225,6 @@ def _spawn_carla_actor(self, req):
225225
carla_actor = self.world.spawn_actor(blueprint, transform, attach_to)
226226
return carla_actor.id
227227

228-
229228
def _create_object_from_actor(self, carla_actor):
230229
"""
231230
create a object for a given carla actor
@@ -239,9 +238,12 @@ def _create_object_from_actor(self, carla_actor):
239238
else:
240239
parent = self._create_object_from_actor(carla_actor.parent)
241240
# calculate relative transform
242-
actor_transform_matrix = trans.ros_pose_to_transform_matrix(trans.carla_transform_to_ros_pose(carla_actor.get_transform()))
243-
parent_transform_matrix = trans.ros_pose_to_transform_matrix(trans.carla_transform_to_ros_pose(carla_actor.parent.get_transform()))
244-
relative_transform_matrix = np.matrix(parent_transform_matrix).getI() * np.matrix(actor_transform_matrix)
241+
actor_transform_matrix = trans.ros_pose_to_transform_matrix(
242+
trans.carla_transform_to_ros_pose(carla_actor.get_transform()))
243+
parent_transform_matrix = trans.ros_pose_to_transform_matrix(
244+
trans.carla_transform_to_ros_pose(carla_actor.parent.get_transform()))
245+
relative_transform_matrix = np.matrix(
246+
parent_transform_matrix).getI() * np.matrix(actor_transform_matrix)
245247
relative_transform = trans.transform_matrix_to_ros_pose(relative_transform_matrix)
246248

247249
parent_id = 0
@@ -251,10 +253,10 @@ def _create_object_from_actor(self, carla_actor):
251253
name = carla_actor.attributes.get("role_name", "")
252254
if not name:
253255
name = str(carla_actor.id)
254-
obj = self._create_object(carla_actor.id, carla_actor.type_id, name, parent_id, relative_transform, carla_actor)
256+
obj = self._create_object(carla_actor.id, carla_actor.type_id, name,
257+
parent_id, relative_transform, carla_actor)
255258
return obj
256259

257-
258260
def _destroy_object(self, actor_id, delete_actor):
259261
if actor_id not in self.actors:
260262
return
@@ -283,12 +285,11 @@ def _create_object(self, uid, type_id, name, attach_to, spawn_pose, carla_actor=
283285
if attach_to != 0:
284286
if attach_to not in self.actors:
285287
raise IndexError("Parent object {} not found".format(attach_to))
286-
288+
287289
parent = self.actors[attach_to]
288290
else:
289291
parent = None
290292

291-
292293
if type_id == TFSensor.get_blueprint_name():
293294
actor = TFSensor(uid=uid, name=name, parent=parent, node=self.node)
294295

carla_ros_bridge/src/carla_ros_bridge/bridge.py

+4-3
Original file line numberDiff line numberDiff line change
@@ -203,7 +203,8 @@ def destroy_object(self, req, response=None):
203203
destroyed_actors = self.actor_factory.destroy_actor(req.id)
204204
response.success = bool(destroyed_actors)
205205
for actor in destroyed_actors:
206-
if actor in self._registered_actors: self._registered_actors.remove(actor)
206+
if actor in self._registered_actors:
207+
self._registered_actors.remove(actor)
207208
return response
208209

209210
def get_blueprints(self, req):
@@ -300,7 +301,7 @@ def _synchronous_mode_update(self):
300301
if not self._all_vehicle_control_commands_received.wait(CarlaRosBridge.VEHICLE_CONTROL_TIMEOUT):
301302
self.logwarn("Timeout ({}s) while waiting for vehicle control commands. "
302303
"Missing command from actor ids {}".format(CarlaRosBridge.VEHICLE_CONTROL_TIMEOUT,
303-
self._expected_ego_vehicle_control_command_ids))
304+
self._expected_ego_vehicle_control_command_ids))
304305
self._all_vehicle_control_commands_received.clear()
305306
self.synchronous_update_finished_event.set()
306307

@@ -324,7 +325,7 @@ def _carla_time_tick(self, carla_snapshot):
324325
self.update_clock(carla_snapshot.timestamp)
325326
self.status_publisher.set_frame(carla_snapshot.frame)
326327
self._update(carla_snapshot.frame,
327-
carla_snapshot.timestamp.elapsed_seconds)
328+
carla_snapshot.timestamp.elapsed_seconds)
328329

329330
def _update(self, frame_id, timestamp):
330331
"""

carla_ros_bridge/src/carla_ros_bridge/carla_status_publisher.py

+1-1
Original file line numberDiff line numberDiff line change
@@ -44,7 +44,7 @@ def __init__(self, synchronous_mode, fixed_delta_seconds, node):
4444
elif ROS_VERSION == 2:
4545
callback_group = ReentrantCallbackGroup()
4646
self.carla_status_publisher = self.node.new_publisher(CarlaStatus, "/carla/status",
47-
callback_group=callback_group)
47+
callback_group=callback_group)
4848
self.publish()
4949

5050
def destroy(self):

carla_ros_bridge/src/carla_ros_bridge/odom_sensor.py

+2-1
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,7 @@ def update(self, frame, timestamp):
6767
odometry.twist.twist = self.parent.get_current_ros_twist_rotated()
6868
except AttributeError:
6969
# parent actor disappeared, do not send tf
70-
self.node.logwarn("OdometrySensor could not publish. parent actor {} not found".format(self.parent.uid))
70+
self.node.logwarn(
71+
"OdometrySensor could not publish. parent actor {} not found".format(self.parent.uid))
7172
return
7273
self.odometry_publisher.publish(odometry)

carla_ros_bridge/src/carla_ros_bridge/sensor.py

+5-3
Original file line numberDiff line numberDiff line change
@@ -158,14 +158,15 @@ def _callback_sensor_data(self, carla_sensor_data):
158158
:param carla_sensor_data: carla sensor data object
159159
:type carla_sensor_data: carla.SensorData
160160
"""
161-
self._callback_active.acquire()
161+
self._callback_active.acquire()
162162
if self.synchronous_mode:
163163
if self.sensor_tick_time:
164164
self.next_data_expected_time = carla_sensor_data.timestamp + \
165165
float(self.sensor_tick_time)
166166
self.queue.put(carla_sensor_data)
167167
else:
168-
self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform), carla_sensor_data.timestamp)
168+
self.publish_tf(trans.carla_transform_to_ros_pose(
169+
carla_sensor_data.transform), carla_sensor_data.timestamp)
169170
self.sensor_data_updated(carla_sensor_data)
170171
self._callback_active.release()
171172

@@ -192,7 +193,8 @@ def _update_synchronous_event_sensor(self, frame):
192193
carla_sensor_data.frame, frame))
193194
self.node.logdebug("{}({}): process {}".format(
194195
self.__class__.__name__, self.get_id(), frame))
195-
self.publish_tf(trans.carla_transform_to_ros_pose(carla_sensor_data.transform), frame)
196+
self.publish_tf(trans.carla_transform_to_ros_pose(
197+
carla_sensor_data.transform), frame)
196198
self.sensor_data_updated(carla_sensor_data)
197199
except queue.Empty:
198200
return

carla_ros_bridge/src/carla_ros_bridge/speedometer_sensor.py

+2-1
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,8 @@ def update(self, frame, timestamp):
6565
transform = self.parent.carla_actor.get_transform()
6666
except AttributeError:
6767
# parent actor disappeared, do not send tf
68-
self.node.logwarn("SpeedometerSensor could not publish. Parent actor {} not found".format(self.parent.uid))
68+
self.node.logwarn(
69+
"SpeedometerSensor could not publish. Parent actor {} not found".format(self.parent.uid))
6970
return
7071

7172
vel_np = np.array([velocity.x, velocity.y, velocity.z])

carla_ros_bridge/src/carla_ros_bridge/tf_sensor.py

+4-3
Original file line numberDiff line numberDiff line change
@@ -61,15 +61,16 @@ def update(self, frame, timestamp):
6161
Function (override) to update this object.
6262
"""
6363
self.parent.get_prefix()
64-
64+
6565
transform = None
6666
try:
6767
transform = self.parent.get_current_ros_transform()
6868
except AttributeError:
6969
# parent actor disappeared, do not send tf
70-
self.node.logwarn("TFSensor could not publish transform. Actor {} not found".format(self.parent.uid))
70+
self.node.logwarn(
71+
"TFSensor could not publish transform. Actor {} not found".format(self.parent.uid))
7172
return
72-
73+
7374
self._tf_broadcaster.sendTransform(TransformStamped(
7475
header=self.get_msg_header("map", timestamp=timestamp),
7576
child_frame_id=self.parent.get_prefix(),

0 commit comments

Comments
 (0)