openpilot is an open source driver assistance system. openpilot performs the functions of Automated Lane Centering and Adaptive Cruise Control for over 200 supported car makes and models.
You can not select more than 25 topics Topics must start with a letter or number, can include dashes ('-') and can be up to 35 characters long.

57 lines
2.0 KiB

import capnp
import cereal.messaging as messaging
from openpilot.common.params import Params
from openpilot.system.manager.process_config import managed_processes
class TestLocationdProc:
LLD_MSGS = ['gpsLocationExternal', 'cameraOdometry', 'carState', 'liveCalibration',
Sensor events splitup (#25714) * PoC of reading sensors via interrupts instead of polling * add Gyro and draft for magn * add more functionality to gpio.cc * change LSM gyro to interrupt * resolve rebase conflict * update BMX accel interrupt impl * add interrupt collector thread to fetch in parallel * change get_event interface to return true on successful read * update BMX gyro interrupt impl * update gpio.h/.cc according to comments * address comments, rename Edgetype enum * Edgetype to EdgeType * update sensor interrupt interface * add error handling, and read fd on trigger * avoid sending empty messages * fix build * use gpiochip * less diff * gpiochip on both edges, but skip falling edge if rising edge is detected * init last_ts with 0 * update sensord testcases * update sensord testsweet * test for pipeline * readd with_process * add null check * move tests update to seperate PR * sensord: improve test coverage (#25683) * update sensord-interrupt testsweet * address review comments * inc stddev threshold * fix format string * add version 0 check again * relax strictness after c3 with bmx tests * relax strictness after tests Co-authored-by: Kurt Nistelberger <kurt.nistelberger@gmail.com> * address PR comments * fix typo * remove 4ms limit, and skip first 0.5sec of data * revert disable_interuppt change to destructor * fix and remove timing skip * make gpiochip generic * sensord port * change from sensorEvents to separated events * fix gyro usage * add splitted sensor tests * modify debug script sensor_data_to_hist.py * refactor get_event interface to remove sensorEvent message type * update locationd to non sensorEvent usage * tmp commit * fix replay * fix accelerometer type * fix sensor to hist debug script * update sensord tests to split events * remove rebase artifacts * port test_sensord.py * small clean up * change cereal to sensorEvents-splitup branch * upate sensorEvents in regen * fix route generation for splitted sensor events * regen cleanUp from sensorEvents change * . * remove light and temp from locationd * add generic init delay per sensor * . * update routes * move bmx gyro/accel to its own channel * adopt sensor tests to bmx channel * remove rebase artifacts * fix sensord test * handle bmx not present * add bmx sockets to regen * . * . * code cleanUp * . * address PR comments * address PR comments * address PR comments * lsm clean up * readd sensorEvents * rever regen.py * . * update replay refs * move channels * fix artifact * bump cereal * update refs * fix timing issue Co-authored-by: Bruce Wayne <batman@workstation-eu-intern2.eu.local> Co-authored-by: gast04 <kurt.nistelberger@gmail.com> Co-authored-by: Willem Melching <willem.melching@gmail.com> Co-authored-by: Adeeb Shihadeh <adeebshihadeh@gmail.com> old-commit-hash: 29d3ed2ce63a65f793dc0ecb553180a0d0fba03e
3 years ago
'accelerometer', 'gyroscope', 'magnetometer']
def setup_method(self):
self.pm = messaging.PubMaster(self.LLD_MSGS)
self.params = Params()
self.params.put_bool("UbloxAvailable", True)
managed_processes['locationd'].prepare()
managed_processes['locationd'].start()
def teardown_method(self):
managed_processes['locationd'].stop()
def get_msg(self, name, t):
try:
msg = messaging.new_message(name)
except capnp.lib.capnp.KjException:
msg = messaging.new_message(name, 0)
if name == "gpsLocationExternal":
msg.gpsLocationExternal.flags = 1
msg.gpsLocationExternal.hasFix = True
msg.gpsLocationExternal.verticalAccuracy = 1.0
msg.gpsLocationExternal.speedAccuracy = 1.0
msg.gpsLocationExternal.bearingAccuracyDeg = 1.0
msg.gpsLocationExternal.vNED = [0.0, 0.0, 0.0]
msg.gpsLocationExternal.latitude = float(self.lat)
msg.gpsLocationExternal.longitude = float(self.lon)
msg.gpsLocationExternal.unixTimestampMillis = t * 1e6
msg.gpsLocationExternal.altitude = float(self.alt)
#if name == "gnssMeasurements":
# msg.gnssMeasurements.measTime = t
# msg.gnssMeasurements.positionECEF.value = [self.x , self.y, self.z]
# msg.gnssMeasurements.positionECEF.std = [0,0,0]
# msg.gnssMeasurements.positionECEF.valid = True
# msg.gnssMeasurements.velocityECEF.value = []
# msg.gnssMeasurements.velocityECEF.std = [0,0,0]
# msg.gnssMeasurements.velocityECEF.valid = True
elif name == 'cameraOdometry':
msg.cameraOdometry.rot = [0.0, 0.0, 0.0]
msg.cameraOdometry.rotStd = [0.0, 0.0, 0.0]
msg.cameraOdometry.trans = [0.0, 0.0, 0.0]
msg.cameraOdometry.transStd = [0.0, 0.0, 0.0]
msg.logMonoTime = t
msg.valid = True
return msg