diff --git a/selfdrive/athena/test.py b/selfdrive/athena/test.py index 0bedfdeb72..b3e1d6921b 100755 --- a/selfdrive/athena/test.py +++ b/selfdrive/athena/test.py @@ -41,8 +41,7 @@ class TestAthenadMethods(unittest.TestCase): start = time.time() while time.time() - start < 1: - msg = messaging.new_message() - msg.init('thermal') + msg = messaging.new_message('thermal') pub_sock.send(msg.to_bytes()) time.sleep(0.01) diff --git a/selfdrive/boardd/tests/boardd_old.py b/selfdrive/boardd/tests/boardd_old.py index 135bde3931..f6ca7eb87d 100755 --- a/selfdrive/boardd/tests/boardd_old.py +++ b/selfdrive/boardd/tests/boardd_old.py @@ -27,8 +27,7 @@ except Exception: # *** serialization functions *** def can_list_to_can_capnp(can_msgs, msgtype='can'): - dat = messaging.new_message() - dat.init(msgtype, len(can_msgs)) + dat = messaging.new_message(msgtype, len(can_msgs)) for i, can_msg in enumerate(can_msgs): if msgtype == 'sendcan': cc = dat.sendcan[i] @@ -168,8 +167,7 @@ def boardd_loop(rate=100): # health packet @ 2hz if (rk.frame % (rate // 2)) == 0: health = can_health() - msg = messaging.new_message() - msg.init('health') + msg = messaging.new_message('health') # store the health to be logged msg.health.voltage = health['voltage'] diff --git a/selfdrive/camerad/test/frame_test.py b/selfdrive/camerad/test/frame_test.py index 802471ea90..2518e80344 100755 --- a/selfdrive/camerad/test/frame_test.py +++ b/selfdrive/camerad/test/frame_test.py @@ -25,8 +25,7 @@ if __name__ == "__main__": idx = 0 while 1: print("send %d" % idx) - dat = messaging.new_message() - dat.init('frame') + dat = messaging.new_message('frame') dat.valid = True dat.frame = { "frameId": idx, diff --git a/selfdrive/controls/controlsd.py b/selfdrive/controls/controlsd.py index 1d4118eb42..8c13578224 100755 --- a/selfdrive/controls/controlsd.py +++ b/selfdrive/controls/controlsd.py @@ -347,8 +347,7 @@ def data_send(sm, pm, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk force_decel = sm['dMonitoringState'].awarenessStatus < 0. # controlsState - dat = messaging.new_message() - dat.init('controlsState') + dat = messaging.new_message('controlsState') dat.valid = CS.canValid dat.controlsState = { "alertText1": AM.alert_text_1, @@ -400,8 +399,7 @@ def data_send(sm, pm, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk pm.send('controlsState', dat) # carState - cs_send = messaging.new_message() - cs_send.init('carState') + cs_send = messaging.new_message('carState') cs_send.valid = CS.canValid cs_send.carState = CS cs_send.carState.events = events @@ -410,21 +408,18 @@ def data_send(sm, pm, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk # carEvents - logged every second or on change events_bytes = events_to_bytes(events) if (sm.frame % int(1. / DT_CTRL) == 0) or (events_bytes != events_prev): - ce_send = messaging.new_message() - ce_send.init('carEvents', len(events)) + ce_send = messaging.new_message('carEvents', len(events)) ce_send.carEvents = events pm.send('carEvents', ce_send) # carParams - logged every 50 seconds (> 1 per segment) if (sm.frame % int(50. / DT_CTRL) == 0): - cp_send = messaging.new_message() - cp_send.init('carParams') + cp_send = messaging.new_message('carParams') cp_send.carParams = CP pm.send('carParams', cp_send) # carControl - cc_send = messaging.new_message() - cc_send.init('carControl') + cc_send = messaging.new_message('carControl') cc_send.valid = CS.canValid cc_send.carControl = CC pm.send('carControl', cc_send) diff --git a/selfdrive/controls/dmonitoringd.py b/selfdrive/controls/dmonitoringd.py index 3c888d7b30..86afb9dcff 100755 --- a/selfdrive/controls/dmonitoringd.py +++ b/selfdrive/controls/dmonitoringd.py @@ -82,8 +82,7 @@ def dmonitoringd_thread(sm=None, pm=None): events = driver_status.update(events, driver_engaged, sm['carState'].cruiseState.enabled, sm['carState'].standstill) # dMonitoringState packet - dat = messaging.new_message() - dat.init('dMonitoringState') + dat = messaging.new_message('dMonitoringState') dat.dMonitoringState = { "events": events, "faceDetected": driver_status.face_detected, diff --git a/selfdrive/controls/gps_plannerd.py b/selfdrive/controls/gps_plannerd.py index 7572a41879..2cca117b09 100755 --- a/selfdrive/controls/gps_plannerd.py +++ b/selfdrive/controls/gps_plannerd.py @@ -283,8 +283,7 @@ def gps_planner_point_selection(): cur_pos = log.ECEFPoint.new_message() cur_pos.x, cur_pos.y, cur_pos.z = map(float, cur_ecef) - m = messaging.new_message() - m.init('gpsPlannerPoints') + m = messaging.new_message('gpsPlannerPoints') m.gpsPlannerPoints.curPos = cur_pos m.gpsPlannerPoints.points = convert_ecef_to_capnp(active_points) m.gpsPlannerPoints.valid = len(active_points) > 10 @@ -293,8 +292,7 @@ def gps_planner_point_selection(): m.gpsPlannerPoints.accelTarget = 0. if cur_track is None else float(cur_track['accel']) gps_planner_points.send(m.to_bytes()) - m = messaging.new_message() - m.init('uiNavigationEvent') + m = messaging.new_message('uiNavigationEvent') m.uiNavigationEvent.status = state m.uiNavigationEvent.type = "none" if instruction is None else instruction['type'] m.uiNavigationEvent.distanceTo = 0. if instruction is None else float(instruction['distance']) @@ -345,8 +343,7 @@ def gps_planner_plan(): valid = points.valid - m = messaging.new_message() - m.init('gpsPlannerPlan') + m = messaging.new_message('gpsPlannerPlan') m.gpsPlannerPlan.valid = valid m.gpsPlannerPlan.poly = poly m.gpsPlannerPlan.trackName = points.trackName diff --git a/selfdrive/controls/lib/long_mpc.py b/selfdrive/controls/lib/long_mpc.py index f694af3771..b83354065f 100644 --- a/selfdrive/controls/lib/long_mpc.py +++ b/selfdrive/controls/lib/long_mpc.py @@ -28,8 +28,7 @@ class LongitudinalMpc(): def send_mpc_solution(self, pm, qp_iterations, calculation_time): qp_iterations = max(0, qp_iterations) - dat = messaging.new_message() - dat.init('liveLongitudinalMpc') + dat = messaging.new_message('liveLongitudinalMpc') dat.liveLongitudinalMpc.xEgo = list(self.mpc_solution[0].x_ego) dat.liveLongitudinalMpc.vEgo = list(self.mpc_solution[0].v_ego) dat.liveLongitudinalMpc.aEgo = list(self.mpc_solution[0].a_ego) diff --git a/selfdrive/controls/lib/pathplanner.py b/selfdrive/controls/lib/pathplanner.py index cee66c6e87..07d06fce55 100644 --- a/selfdrive/controls/lib/pathplanner.py +++ b/selfdrive/controls/lib/pathplanner.py @@ -181,8 +181,7 @@ class PathPlanner(): self.solution_invalid_cnt = 0 plan_solution_valid = self.solution_invalid_cnt < 2 - plan_send = messaging.new_message() - plan_send.init('pathPlan') + plan_send = messaging.new_message('pathPlan') plan_send.valid = sm.all_alive_and_valid(service_list=['carState', 'controlsState', 'liveParameters', 'model']) plan_send.pathPlan.laneWidth = float(self.LP.lane_width) plan_send.pathPlan.dPoly = [float(x) for x in self.LP.d_poly] @@ -206,8 +205,7 @@ class PathPlanner(): pm.send('pathPlan', plan_send) if LOG_MPC: - dat = messaging.new_message() - dat.init('liveMpc') + dat = messaging.new_message('liveMpc') dat.liveMpc.x = list(self.mpc_solution[0].x) dat.liveMpc.y = list(self.mpc_solution[0].y) dat.liveMpc.psi = list(self.mpc_solution[0].psi) diff --git a/selfdrive/controls/lib/planner.py b/selfdrive/controls/lib/planner.py index 1d6140a816..7e6a126e47 100755 --- a/selfdrive/controls/lib/planner.py +++ b/selfdrive/controls/lib/planner.py @@ -214,8 +214,7 @@ class Planner(): radar_can_error = car.RadarData.Error.canError in radar_errors # **** send the plan **** - plan_send = messaging.new_message() - plan_send.init('plan') + plan_send = messaging.new_message('plan') plan_send.valid = sm.all_alive_and_valid(service_list=['carState', 'controlsState', 'radarState']) diff --git a/selfdrive/controls/radard.py b/selfdrive/controls/radard.py index a99a0bdfbf..0b8523313f 100755 --- a/selfdrive/controls/radard.py +++ b/selfdrive/controls/radard.py @@ -163,8 +163,7 @@ class RadarD(): self.tracks[idens[idx]].reset_a_lead(aLeadK, aLeadTau) # *** publish radarState *** - dat = messaging.new_message() - dat.init('radarState') + dat = messaging.new_message('radarState') dat.valid = sm.all_alive_and_valid(service_list=['controlsState', 'model']) dat.radarState.mdMonoTime = self.last_md_ts dat.radarState.canMonoTimes = list(rr.canMonoTimes) @@ -223,8 +222,7 @@ def radard_thread(sm=None, pm=None, can_sock=None): # *** publish tracks for UI debugging (keep last) *** tracks = RD.tracks - dat = messaging.new_message() - dat.init('liveTracks', len(tracks)) + dat = messaging.new_message('liveTracks', len(tracks)) for cnt, ids in enumerate(sorted(tracks.keys())): dat.liveTracks[cnt] = { diff --git a/selfdrive/controls/tests/test_following_distance.py b/selfdrive/controls/tests/test_following_distance.py index 63545e6ee4..11995c6c78 100644 --- a/selfdrive/controls/tests/test_following_distance.py +++ b/selfdrive/controls/tests/test_following_distance.py @@ -46,8 +46,7 @@ def run_following_distance_simulation(v_lead, t_end=200.0): dt) # Setup CarState - CS = messaging.new_message() - CS.init('carState') + CS = messaging.new_message('carState') CS.carState.vEgo = v_ego CS.carState.aEgo = a_ego diff --git a/selfdrive/debug/internal/cycle_alerts.py b/selfdrive/debug/internal/cycle_alerts.py index 6c5036fb63..20b0a8dd46 100644 --- a/selfdrive/debug/internal/cycle_alerts.py +++ b/selfdrive/debug/internal/cycle_alerts.py @@ -28,8 +28,7 @@ def cycle_alerts(duration_millis, alerts=None): last_pop_millis = now_millis() print('sending {}'.format(str(alert))) - dat = messaging.new_message() - dat.init('controlsState') + dat = messaging.new_message('controlsState') dat.controlsState.alertType = alert.alert_type dat.controlsState.alertText1 = alert.alert_text_1 diff --git a/selfdrive/debug/internal/messaging_benchmark.py b/selfdrive/debug/internal/messaging_benchmark.py index d7acdd5c04..2fb5c32a3e 100755 --- a/selfdrive/debug/internal/messaging_benchmark.py +++ b/selfdrive/debug/internal/messaging_benchmark.py @@ -6,8 +6,7 @@ import cereal.messaging as messaging def init_message_bench(N=100000): t = time.time() for _ in range(N): - dat = messaging.new_message() - dat.init('controlsState') + dat = messaging.new_message('controlsState') dt = time.time() - t print("Init message %d its, %f s" % (N, dt)) diff --git a/selfdrive/debug/internal/mock_process/fake_UiNavigationEvent.py b/selfdrive/debug/internal/mock_process/fake_UiNavigationEvent.py index 50eb31bb65..ac4ce168c8 100755 --- a/selfdrive/debug/internal/mock_process/fake_UiNavigationEvent.py +++ b/selfdrive/debug/internal/mock_process/fake_UiNavigationEvent.py @@ -9,8 +9,7 @@ def mock(): traffic_events = messaging.pub_sock('uiNavigationEvent') while 1: - m = messaging.new_message() - m.init('uiNavigationEvent') + m = messaging.new_message('uiNavigationEvent') m.uiNavigationEvent.type = log.UiNavigationEvent.Type.mergeRight m.uiNavigationEvent.status = log.UiNavigationEvent.Status.active m.uiNavigationEvent.distanceTo = 100. diff --git a/selfdrive/debug/internal/mock_process/fake_controls_state.py b/selfdrive/debug/internal/mock_process/fake_controls_state.py index 143ec23212..2cc9a9cb89 100755 --- a/selfdrive/debug/internal/mock_process/fake_controls_state.py +++ b/selfdrive/debug/internal/mock_process/fake_controls_state.py @@ -12,8 +12,7 @@ if __name__ == "__main__": rk = Ratekeeper(100) while 1: - dat = messaging.new_message() - dat.init('controlsState') + dat = messaging.new_message('controlsState') dat.controlsState.vEgo = 25. dat.controlsState.enabled = True diff --git a/selfdrive/debug/internal/mock_process/fake_fusion_state.py b/selfdrive/debug/internal/mock_process/fake_fusion_state.py index be08e1c4da..f4c61e99d1 100755 --- a/selfdrive/debug/internal/mock_process/fake_fusion_state.py +++ b/selfdrive/debug/internal/mock_process/fake_fusion_state.py @@ -15,8 +15,7 @@ def leadRange(start, end, step): def mock_lead(): radarState = messaging.pub_sock('radarState') while 1: - m = messaging.new_message() - m.init('radarState') + m = messaging.new_message('radarState') m.radarState.leadOne.status = True for x in leadRange(3.0, 65.0, 0.005): m.radarState.leadOne.dRel = x diff --git a/selfdrive/debug/internal/mock_process/fake_gps.py b/selfdrive/debug/internal/mock_process/fake_gps.py index e540ef52b4..b3a23ba6e3 100755 --- a/selfdrive/debug/internal/mock_process/fake_gps.py +++ b/selfdrive/debug/internal/mock_process/fake_gps.py @@ -29,8 +29,7 @@ if __name__ == '__main__': for point in cycle(path_stopped_5s_then_moving): print('sending gpsLocation from point: {}'.format(str(point))) - dat = messaging.new_message() - dat.init('gpsLocation') + dat = messaging.new_message('gpsLocation') dat.gpsLocation.latitude = point['lat'] dat.gpsLocation.longitude = point['lng'] dat.gpsLocation.speed = point['speed'] diff --git a/selfdrive/debug/internal/mock_process/fake_gps_external.py b/selfdrive/debug/internal/mock_process/fake_gps_external.py index 34a91530d7..33dae6d510 100755 --- a/selfdrive/debug/internal/mock_process/fake_gps_external.py +++ b/selfdrive/debug/internal/mock_process/fake_gps_external.py @@ -11,8 +11,7 @@ if __name__ == '__main__': gpsLocationExternal = messaging.pub_sock('gpsLocationExternal') while True: - dat = messaging.new_message() - dat.init('gpsLocationExternal') + dat = messaging.new_message('gpsLocationExternal') dat.gpsLocationExternal.latitude = 37.6513687 dat.gpsLocationExternal.longitude = -122.4535056 dat.gpsLocationExternal.speed = 28.2 diff --git a/selfdrive/debug/internal/mock_process/fake_liveMpc.py b/selfdrive/debug/internal/mock_process/fake_liveMpc.py index cf4ecbf8e1..f7471b1aef 100755 --- a/selfdrive/debug/internal/mock_process/fake_liveMpc.py +++ b/selfdrive/debug/internal/mock_process/fake_liveMpc.py @@ -9,9 +9,8 @@ from cereal import log def mock_x(): liveMpc = messaging.pub_sock('liveMpc') while 1: - m = messaging.new_message() + m = messaging.new_message('liveMpc') mx = [] - m.init('liveMpc') for x in range(0, 100): mx.append(x*1.0) m.liveMpc.x = mx diff --git a/selfdrive/debug/internal/mock_process/fake_trafficsignd.py b/selfdrive/debug/internal/mock_process/fake_trafficsignd.py index 7d5a06046c..4562e1fcd1 100755 --- a/selfdrive/debug/internal/mock_process/fake_trafficsignd.py +++ b/selfdrive/debug/internal/mock_process/fake_trafficsignd.py @@ -9,8 +9,7 @@ def mock(): traffic_events = messaging.pub_sock('trafficEvents') while 1: - m = messaging.new_message() - m.init('trafficEvents', 1) + m = messaging.new_message('trafficEvents', 1) m.trafficEvents[0].type = log.TrafficEvent.Type.stopSign m.trafficEvents[0].resuming = False m.trafficEvents[0].distance = 100. diff --git a/selfdrive/debug/internal/send_alert.py b/selfdrive/debug/internal/send_alert.py index 699d51e8e1..2b5df82bd3 100644 --- a/selfdrive/debug/internal/send_alert.py +++ b/selfdrive/debug/internal/send_alert.py @@ -10,8 +10,7 @@ if __name__ == "__main__": controls_state = messaging.pub_sock('controlsState') while 1: - dat = messaging.new_message() - dat.init('controlsState') + dat = messaging.new_message('controlsState') dat.controlsState.alertText1 = "alert text 1" dat.controlsState.alertText2 = "alert text 2" diff --git a/selfdrive/debug/show_matching_cars.py b/selfdrive/debug/show_matching_cars.py index df2b703635..273ae1469b 100755 --- a/selfdrive/debug/show_matching_cars.py +++ b/selfdrive/debug/show_matching_cars.py @@ -16,8 +16,7 @@ candidate_cars = all_known_cars() for addr, l in fingerprint.items(): - dat = messaging.new_message() - dat.init('can', 1) + dat = messaging.new_message('can', 1) msg = dat.can[0] msg.address = addr diff --git a/selfdrive/locationd/calibrationd.py b/selfdrive/locationd/calibrationd.py index 357dd1c3dc..3757a0b8a1 100755 --- a/selfdrive/locationd/calibrationd.py +++ b/selfdrive/locationd/calibrationd.py @@ -120,8 +120,7 @@ class Calibrator(): calib = get_calib_from_vp(self.vp) extrinsic_matrix = get_view_frame_from_road_frame(0, calib[1], calib[2], model_height) - cal_send = messaging.new_message() - cal_send.init('liveCalibration') + cal_send = messaging.new_message('liveCalibration') cal_send.liveCalibration.calStatus = self.cal_status cal_send.liveCalibration.calPerc = min(100 * (self.valid_blocks * BLOCK_SIZE + self.idx) // (INPUTS_NEEDED * BLOCK_SIZE), 100) cal_send.liveCalibration.extrinsicMatrix = [float(x) for x in extrinsic_matrix.flatten()] diff --git a/selfdrive/locationd/locationd.py b/selfdrive/locationd/locationd.py old mode 100755 new mode 100644 index 4c958f139f..001f6d2e9f --- a/selfdrive/locationd/locationd.py +++ b/selfdrive/locationd/locationd.py @@ -255,10 +255,9 @@ def locationd_thread(sm, pm, disabled_logs=[]): if localizer.filter_ready and sm.updated['gpsLocationExternal']: t = sm.logMonoTime['gpsLocationExternal'] - msg = messaging.new_message() + msg = messaging.new_message('liveLocationKalman') msg.logMonoTime = t - msg.init('liveLocationKalman') msg.liveLocationKalman = localizer.liveLocationMsg(t * 1e-9) pm.send('liveLocationKalman', msg) diff --git a/selfdrive/locationd/paramsd.py b/selfdrive/locationd/paramsd.py index 96bfc1dcff..1eca908982 100755 --- a/selfdrive/locationd/paramsd.py +++ b/selfdrive/locationd/paramsd.py @@ -81,10 +81,9 @@ def main(sm=None, pm=None): # TODO: Change KF to allow mass, etc to be inputs in predict step if sm.updated['carState']: - msg = messaging.new_message() + msg = messaging.new_message('liveParameters') msg.logMonoTime = sm.logMonoTime['carState'] - msg.init('liveParameters') msg.liveParameters.valid = True # TODO: Check if learned values are sane msg.liveParameters.posenetValid = True msg.liveParameters.sensorValid = True diff --git a/selfdrive/loggerd/ethernetsniffer.py b/selfdrive/loggerd/ethernetsniffer.py index 969c87f932..9f17c29d7c 100755 --- a/selfdrive/loggerd/ethernetsniffer.py +++ b/selfdrive/loggerd/ethernetsniffer.py @@ -8,8 +8,7 @@ def main(): ethernetData = messaging.pub_sock('ethernetData') for ts, pkt in pcap.pcap('eth0'): - dat = messaging.new_message() - dat.init('ethernetData', 1) + dat = messaging.new_message('ethernetData', 1) dat.ethernetData[0].ts = ts dat.ethernetData[0].pkt = str(pkt) ethernetData.send(dat.to_bytes()) diff --git a/selfdrive/mapd/mapd.py b/selfdrive/mapd/mapd.py index 0e337e45d4..85862befaa 100755 --- a/selfdrive/mapd/mapd.py +++ b/selfdrive/mapd/mapd.py @@ -230,8 +230,7 @@ def mapsd_thread(): query_lock.release() - dat = messaging.new_message() - dat.init('liveMapData') + dat = messaging.new_message('liveMapData') if last_gps is not None: dat.liveMapData.lastGps = last_gps diff --git a/selfdrive/test/longitudinal_maneuvers/plant.py b/selfdrive/test/longitudinal_maneuvers/plant.py index 2170cb71f7..7d6b24d438 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant.py +++ b/selfdrive/test/longitudinal_maneuvers/plant.py @@ -357,8 +357,7 @@ class Plant(): # Fake sockets that controlsd subscribes to - live_parameters = messaging.new_message() - live_parameters.init('liveParameters') + live_parameters = messaging.new_message('liveParameters') live_parameters.liveParameters.valid = True live_parameters.liveParameters.sensorValid = True live_parameters.liveParameters.posenetValid = True @@ -366,19 +365,16 @@ class Plant(): live_parameters.liveParameters.stiffnessFactor = 1.0 Plant.live_params.send(live_parameters.to_bytes()) - driver_state = messaging.new_message() - driver_state.init('driverState') + driver_state = messaging.new_message('driverState') driver_state.driverState.faceOrientation = [0.] * 3 driver_state.driverState.facePosition = [0.] * 2 Plant.driverState.send(driver_state.to_bytes()) - health = messaging.new_message() - health.init('health') + health = messaging.new_message('health') health.health.controlsAllowed = True Plant.health.send(health.to_bytes()) - thermal = messaging.new_message() - thermal.init('thermal') + thermal = messaging.new_message('thermal') thermal.thermal.freeSpace = 1. thermal.thermal.batteryPercent = 100 Plant.thermal.send(thermal.to_bytes()) @@ -386,10 +382,8 @@ class Plant(): # ******** publish a fake model going straight and fake calibration ******** # note that this is worst case for MPC, since model will delay long mpc by one time step if publish_model and self.frame % 5 == 0: - md = messaging.new_message() - cal = messaging.new_message() - md.init('model') - cal.init('liveCalibration') + md = messaging.new_message('model') + cal = messaging.new_message('liveCalibration') md.model.frameId = 0 for x in [md.model.path, md.model.leftLane, md.model.rightLane]: x.points = [0.0]*50 diff --git a/selfdrive/test/longitudinal_maneuvers/plant_ui.py b/selfdrive/test/longitudinal_maneuvers/plant_ui.py index f4b7715e38..3c73f83291 100755 --- a/selfdrive/test/longitudinal_maneuvers/plant_ui.py +++ b/selfdrive/test/longitudinal_maneuvers/plant_ui.py @@ -65,8 +65,7 @@ if __name__ == "__main__": else: cruise_buttons = 0 - md = messaging.new_message() - md.init('model') + md = messaging.new_message('model') md.model.frameId = 0 for x in [md.model.path, md.model.leftLane, md.model.rightLane]: x.points = [0.0]*50 diff --git a/selfdrive/test/process_replay/process_replay.py b/selfdrive/test/process_replay/process_replay.py index 129bb85952..b8288987b1 100755 --- a/selfdrive/test/process_replay/process_replay.py +++ b/selfdrive/test/process_replay/process_replay.py @@ -61,8 +61,7 @@ class FakeSocket: class DumbSocket: def __init__(self, s=None): if s is not None: - dat = messaging.new_message() - dat.init(s) + dat = messaging.new_message(s) self.data = dat.to_bytes() def receive(self, non_blocking=False): @@ -108,11 +107,10 @@ class FakePubMaster(messaging.PubMaster): self.sock = {} self.last_updated = None for s in services: - data = messaging.new_message() try: - data.init(s) + data = messaging.new_message(s) except: - data.init(s, 0) + data = messaging.new_message(s, 0) self.data[s] = data.as_reader() self.sock[s] = DumbSocket() self.send_called = threading.Event() diff --git a/selfdrive/thermald.py b/selfdrive/thermald.py index 647497b799..d62d6e962c 100755 --- a/selfdrive/thermald.py +++ b/selfdrive/thermald.py @@ -45,8 +45,7 @@ def read_tz(x, clip=True): return ret def read_thermal(): - dat = messaging.new_message() - dat.init('thermal') + dat = messaging.new_message('thermal') dat.thermal.cpu0 = read_tz(5) dat.thermal.cpu1 = read_tz(7) dat.thermal.cpu2 = read_tz(10) diff --git a/tools/carcontrols/debug_controls.py b/tools/carcontrols/debug_controls.py index 527ef42fc0..9ce98568d4 100755 --- a/tools/carcontrols/debug_controls.py +++ b/tools/carcontrols/debug_controls.py @@ -84,14 +84,12 @@ def steer_thread(): sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan')) # broadcast carState - cs_send = messaging.new_message() - cs_send.init('carState') + cs_send = messaging.new_message('carState') cs_send.carState = copy(CS) carstate.send(cs_send.to_bytes()) # broadcast carControl - cc_send = messaging.new_message() - cc_send.init('carControl') + cc_send = messaging.new_message('carControl') cc_send.carControl = copy(CC) carcontrol.send(cc_send.to_bytes()) diff --git a/tools/carcontrols/joystickd.py b/tools/carcontrols/joystickd.py index c80deec606..58235f450b 100755 --- a/tools/carcontrols/joystickd.py +++ b/tools/carcontrols/joystickd.py @@ -55,8 +55,7 @@ def joystick_thread(): for b in range(joystick.get_numbuttons()): buttons.append(bool(joystick.get_button(b))) - dat = messaging.new_message() - dat.init('testJoystick') + dat = messaging.new_message('testJoystick') dat.testJoystick.axes = axes dat.testJoystick.buttons = buttons joystick_sock.send(dat.to_bytes()) diff --git a/tools/sim/bridge.py b/tools/sim/bridge.py index 6e80eb12f0..6a62df40d5 100755 --- a/tools/sim/bridge.py +++ b/tools/sim/bridge.py @@ -30,8 +30,7 @@ def cam_callback(image): img = np.reshape(img, (H, W, 4)) img = img[:, :, [0,1,2]].copy() - dat = messaging.new_message() - dat.init('frame') + dat = messaging.new_message('frame') dat.frame = { "frameId": image.frame, "image": img.tostring(), @@ -42,8 +41,7 @@ def cam_callback(image): def imu_callback(imu): #print(imu, imu.accelerometer) - dat = messaging.new_message() - dat.init('sensorEvents', 2) + dat = messaging.new_message('sensorEvents', 2) dat.sensorEvents[0].sensor = 4 dat.sensorEvents[0].type = 0x10 dat.sensorEvents[0].init('acceleration') @@ -59,8 +57,7 @@ def health_function(): pm = messaging.PubMaster(['health']) rk = Ratekeeper(1.0) while 1: - dat = messaging.new_message() - dat.init('health') + dat = messaging.new_message('health') dat.valid = True dat.health = { 'ignitionLine': True, @@ -73,8 +70,7 @@ def health_function(): def fake_driver_monitoring(): pm = messaging.PubMaster(['driverState']) while 1: - dat = messaging.new_message() - dat.init('driverState') + dat = messaging.new_message('driverState') dat.driverState.faceProb = 1.0 pm.send('driverState', dat) time.sleep(0.1) diff --git a/tools/streamer/streamerd.py b/tools/streamer/streamerd.py index 95d34735f1..8788eafd29 100755 --- a/tools/streamer/streamerd.py +++ b/tools/streamer/streamerd.py @@ -67,8 +67,7 @@ def receiver_thread(): #print 'ms to make yuv:', (t1-t2)*1000 #print 'tsEof:', ts - dat = messaging.new_message() - dat.init('frame') + dat = messaging.new_message('frame') dat.frame.image = yuv_img dat.frame.timestampEof = ts dat.frame.transform = map(float, list(np.eye(3).flatten()))