diff --git a/README.md b/README.md index cc9cd9145..a07953b97 100644 --- a/README.md +++ b/README.md @@ -1,4 +1,4 @@ -What is cereal? [![cereal tests](https://github.com/commaai/cereal/workflows/Tests/badge.svg?event=push)](https://github.com/commaai/cereal/actions) [![codecov](https://codecov.io/gh/commaai/cereal/branch/master/graph/badge.svg)](https://codecov.io/gh/commaai/cereal) +What is cereal? [![cereal tests](https://github.com/commaai/cereal/workflows/tests/badge.svg?event=push)](https://github.com/commaai/cereal/actions) [![codecov](https://codecov.io/gh/commaai/cereal/branch/master/graph/badge.svg)](https://codecov.io/gh/commaai/cereal) ---- cereal is both a messaging spec for robotics systems as well as generic high performance IPC pub sub messaging with a single publisher and multiple subscribers. diff --git a/car.capnp b/car.capnp index e05c348e6..cdc98e6cd 100644 --- a/car.capnp +++ b/car.capnp @@ -17,7 +17,8 @@ struct CarEvent @0x9b1657f34caf3ad3 { immediateDisable @6 :Bool; preEnable @7 :Bool; permanent @8 :Bool; # alerts presented regardless of openpilot state - override @9 :Bool; + overrideLateral @10 :Bool; + overrideLongitudinal @9 :Bool; enum EventName @0xbaa8c5d505f727de { canError @0; @@ -33,8 +34,9 @@ struct CarEvent @0x9b1657f34caf3ad3 { buttonCancel @11; buttonEnable @12; pedalPressed @13; # exits active state - pedalPressedPreEnable @73; # added during pre-enable state for either pedal + preEnableStandstill @73; # added during pre-enable state with brake gasPressedOverride @108; # added when user is pressing gas with no disengage on gas + steerOverride @114; cruiseDisabled @14; speedTooLow @17; outOfSpace @18; @@ -44,7 +46,6 @@ struct CarEvent @0x9b1657f34caf3ad3 { controlsMismatch @22; pcmEnable @23; pcmDisable @24; - noTarget @25; radarFault @26; brakeHold @28; parkBrake @29; @@ -64,6 +65,7 @@ struct CarEvent @0x9b1657f34caf3ad3 { lowBattery @48; vehicleModelInvalid @50; accFaulted @51; + accFaultedTemp @115; sensorDataInvalid @52; commIssue @53; commIssueAvgFreq @109; @@ -135,6 +137,7 @@ struct CarEvent @0x9b1657f34caf3ad3 { modelLagWarningDEPRECATED @93; startupOneplusDEPRECATED @82; startupFuzzyFingerprintDEPRECATED @97; + noTargetDEPRECATED @25; } } @@ -165,6 +168,7 @@ struct CarState { # brake pedal, 0.0-1.0 brake @5 :Float32; # this is user pedal only brakePressed @6 :Bool; # this is user pedal only + regenBraking @45 :Bool; # this is user pedal only parkingBrake @39 :Bool; brakeHoldActive @38 :Bool; @@ -313,6 +317,9 @@ struct CarControl { # Actuator commands as computed by controlsd actuators @6 :Actuators; + leftBlinker @15: Bool; + rightBlinker @16: Bool; + # Any car specific rate limits or quirks applied by # the CarController are reflected in actuatorsOutput # and matches what is sent to the car @@ -330,8 +337,12 @@ struct CarControl { brake @1: Float32; # range from -1.0 - 1.0 steer @2: Float32; + # value sent over can to the car + steerOutputCan @8: Float32; steeringAngleDeg @3: Float32; + curvature @7: Float32; + speed @6: Float32; # m/s accel @4: Float32; # m/s^2 longControlState @5: LongControlState; @@ -340,15 +351,14 @@ struct CarControl { off @0; pid @1; stopping @2; - - startingDEPRECATED @3; + starting @3; } - } struct CruiseControl { cancel @0: Bool; resume @1: Bool; + override @4: Bool; speedOverrideDEPRECATED @2: Float32; accelOverrideDEPRECATED @3: Float32; } @@ -414,23 +424,18 @@ struct CarParams { enableGasInterceptor @2 :Bool; pcmCruise @3 :Bool; # is openpilot's state tied to the PCM's cruise state? enableDsu @5 :Bool; # driving support unit - enableApgs @6 :Bool; # advanced parking guidance system enableBsm @56 :Bool; # blind spot monitoring flags @64 :UInt32; # flags for car specific quirks + experimentalLongitudinalAvailable @71 :Bool; minEnableSpeed @7 :Float32; minSteerSpeed @8 :Float32; - maxSteeringAngleDeg @54 :Float32; safetyConfigs @62 :List(SafetyConfig); alternativeExperience @65 :Int16; # panda flag for features like no disengage on gas - maxLateralAccel @68 :Float32; - steerMaxBPDEPRECATED @11 :List(Float32); - steerMaxVDEPRECATED @12 :List(Float32); - gasMaxBPDEPRECATED @13 :List(Float32); - gasMaxVDEPRECATED @14 :List(Float32); - brakeMaxBPDEPRECATED @15 :List(Float32); - brakeMaxVDEPRECATED @16 :List(Float32); + # Car docs fields + maxLateralAccel @68 :Float32; + autoResumeSng @69 :Bool; # describes whether car can resume from a stop automatically # things about the car in the manual mass @17 :Float32; # [kg] curb weight: all fluids no cargo @@ -458,12 +463,13 @@ struct CarParams { vEgoStopping @29 :Float32; # Speed at which the car goes into stopping state vEgoStarting @59 :Float32; # Speed at which the car goes into starting state - directAccelControl @30 :Bool; # Does the car have direct accel control or just gas/brake - stoppingControl @31 :Bool; # Does the car allows full control even at lows speeds when stopping - stopAccel @60 :Float32; # Required acceleration to keep vehicle stationary + stoppingControl @31 :Bool; # Does the car allow full control even at lows speeds when stopping steerControlType @34 :SteerControlType; radarOffCan @35 :Bool; # True when radar objects aren't visible on CAN + stopAccel @60 :Float32; # Required acceleration to keep vehicle stationary stoppingDecelRate @52 :Float32; # m/s^2/s while trying to stop + startAccel @32 :Float32; # Required acceleration to get car moving + startingState @70 :Bool; # Does this car make use of special starting state steerActuatorDelay @36 :Float32; # Steering wheel actuator delay in seconds longitudinalActuatorDelayLowerBound @61 :Float32; # Gas/Brake actuator delay in seconds, lower bound @@ -507,6 +513,8 @@ struct CarParams { friction @3 :Float32; kf @4 :Float32; steeringAngleDeadzoneDeg @5 :Float32; + latAccelFactor @6 :Float32; + latAccelOffset @7 :Float32; } struct LongitudinalPIDTuning { @@ -584,6 +592,7 @@ struct CarParams { enum SteerControlType { torque @0; angle @1; + curvature @2; } enum TransmissionType { @@ -607,7 +616,7 @@ struct CarParams { enum Ecu { eps @0; - esp @1; + abs @1; fwdRadar @2; fwdCamera @3; engine @4; @@ -617,6 +626,10 @@ struct CarParams { gateway @10; # can gateway hud @11; # heads up display combinationMeter @12; # instrument cluster + electricBrakeBooster @15; + shiftByWire @16; + adas @19; + cornerRadar @21; # Toyota only dsu @6; @@ -625,8 +638,12 @@ struct CarParams { # Honda only vsa @13; # Vehicle Stability Assist programmedFuelInjection @14; - electricBrakeBooster @15; - shiftByWire @16; + + # Chrysler only + hcp @18; # Hybrid Control Processor + + # Hyundai only + vcu @20; # Vehicle (Motor) Control Unit debug @17; } @@ -643,6 +660,7 @@ struct CarParams { } enableCameraDEPRECATED @4 :Bool; + enableApgsDEPRECATED @6 :Bool; steerRateCostDEPRECATED @33 :Float32; isPandaBlackDEPRECATED @39 :Bool; hasStockCameraDEPRECATED @57 :Bool; @@ -650,7 +668,14 @@ struct CarParams { safetyModelDEPRECATED @9 :SafetyModel; safetyModelPassiveDEPRECATED @42 :SafetyModel = silent; minSpeedCanDEPRECATED @51 :Float32; - startAccelDEPRECATED @32 :Float32; communityFeatureDEPRECATED @46: Bool; startingAccelRateDEPRECATED @53 :Float32; + steerMaxBPDEPRECATED @11 :List(Float32); + steerMaxVDEPRECATED @12 :List(Float32); + gasMaxBPDEPRECATED @13 :List(Float32); + gasMaxVDEPRECATED @14 :List(Float32); + brakeMaxBPDEPRECATED @15 :List(Float32); + brakeMaxVDEPRECATED @16 :List(Float32); + directAccelControlDEPRECATED @30 :Bool; + maxSteeringAngleDegDEPRECATED @54 :Float32; } diff --git a/log.capnp b/log.capnp index ef013261e..0f8f8663a 100644 --- a/log.capnp +++ b/log.capnp @@ -137,6 +137,7 @@ struct FrameData { gain @15 :Float32; # This includes highConversionGain if enabled measuredGreyFraction @21 :Float32; targetGreyFraction @22 :Float32; + exposureValPercent @27 :Float32; # Focus lensPos @11 :Int32; @@ -150,10 +151,7 @@ struct FrameData { transform @10 :List(Float32); - androidCaptureResult @9 :AndroidCaptureResult; - image @6 :Data; - globalGainDEPRECATED @5 :Int32; temperaturesC @24 :List(Float32); @@ -164,6 +162,15 @@ struct FrameData { front @3; } + sensor @26 :ImageSensor; + enum ImageSensor { + unknown @0; + ar0321 @1; + ox03c10 @2; + } + + globalGainDEPRECATED @5 :Int32; + androidCaptureResultDEPRECATED @9 :AndroidCaptureResult; struct AndroidCaptureResult { sensitivity @0 :Int32; frameDuration @1 :Int64; @@ -220,9 +227,9 @@ struct SensorEventData { fiber @2; velodyne @3; # Velodyne IMU bno055 @4; # Bosch accelerometer - lsm6ds3 @5; # accelerometer (c2) - bmp280 @6; # barometer (c2) - mmc3416x @7; # magnetometer (c2) + lsm6ds3 @5; # includes LSM6DS3 and LSM6DS3TR, TR = tape reel + bmp280 @6; # barometer + mmc3416x @7; # magnetometer bmx055 @8; rpr0521 @9; lsm6ds3trc @10; @@ -290,7 +297,6 @@ struct CanData { } struct DeviceState @0xa4d8b5af2aa492eb { - usbOnline @12 :Bool; networkType @22 :NetworkType; networkInfo @31 :NetworkInfo; networkStrength @24 :NetworkStrength; @@ -308,10 +314,6 @@ struct DeviceState @0xa4d8b5af2aa492eb { cpuUsagePercent @34 :List(Int8); # per-core cpu usage # power - batteryPercent @8 :Int16; - batteryCurrent @15 :Int32; - chargingError @17 :Bool; - chargingDisabled @18 :Bool; offroadPowerUsageUwh @23 :UInt32; carBatteryCapacityUwh @25 :UInt32; powerDrawW @40 :Float32; @@ -388,31 +390,44 @@ struct DeviceState @0xa4d8b5af2aa492eb { batteryStatusDEPRECATED @9 :Text; batteryVoltageDEPRECATED @16 :Int32; batteryTempCDEPRECATED @29 :Float32; + batteryPercentDEPRECATED @8 :Int16; + batteryCurrentDEPRECATED @15 :Int32; + chargingErrorDEPRECATED @17 :Bool; + chargingDisabledDEPRECATED @18 :Bool; + usbOnlineDEPRECATED @12 :Bool; } struct PandaState @0xa7649e2575e4591e { ignitionLine @2 :Bool; - controlsAllowed @3 :Bool; gasInterceptorDetected @4 :Bool; - canSendErrs @7 :UInt32; - canFwdErrs @8 :UInt32; - canRxErrs @19 :UInt32; + rxBufferOverflow @7 :UInt32; + txBufferOverflow @8 :UInt32; gmlanSendErrs @9 :UInt32; pandaType @10 :PandaType; ignitionCan @13 :Bool; - safetyModel @14 :Car.CarParams.SafetyModel; - safetyParam @27 :UInt16; - alternativeExperience @23 :Int16; faultStatus @15 :FaultStatus; powerSaveEnabled @16 :Bool; uptime @17 :UInt32; faults @18 :List(FaultType); harnessStatus @21 :HarnessStatus; heartbeatLost @22 :Bool; - blockedCnt @24 :UInt32; interruptLoad @25 :Float32; fanPower @28 :UInt8; + # can health + canState0 @29 :PandaCanState; + canState1 @30 :PandaCanState; + canState2 @31 :PandaCanState; + + # safety stuff + controlsAllowed @3 :Bool; + safetyRxInvalid @19 :UInt32; + safetyTxBlocked @24 :UInt32; + safetyModel @14 :Car.CarParams.SafetyModel; + safetyParam @27 :UInt16; + alternativeExperience @23 :Int16; + safetyRxChecksInvalid @32 :Bool; + enum FaultStatus { none @0; faultTemp @1; @@ -443,6 +458,8 @@ struct PandaState @0xa7649e2575e4591e { interruptRateClockSource @20; interruptRateTick @21; interruptRateExti @22; + interruptRateSpi @23; + interruptRateUart7 @24; # Update max fault type in boardd when adding faults } @@ -455,6 +472,8 @@ struct PandaState @0xa7649e2575e4591e { uno @5; dos @6; redPanda @7; + redPandaV2 @8; + tres @9; } enum HarnessStatus { @@ -468,9 +487,44 @@ struct PandaState @0xa7649e2575e4591e { currentDEPRECATED @1 :UInt32; hasGpsDEPRECATED @6 :Bool; fanSpeedRpmDEPRECATED @11 :UInt16; - usbPowerModeDEPRECATED @12 :PeripheralState.UsbPowerMode; + usbPowerModeDEPRECATED @12 :PeripheralState.UsbPowerModeDEPRECATED; safetyParamDEPRECATED @20 :Int16; safetyParam2DEPRECATED @26 :UInt32; + + struct PandaCanState { + busOff @0 :Bool; + busOffCnt @1 :UInt32; + errorWarning @2 :Bool; + errorPassive @3 :Bool; + lastError @4 :LecErrorCode; + lastStoredError @5 :LecErrorCode; + lastDataError @6 :LecErrorCode; + lastDataStoredError @7 :LecErrorCode; + receiveErrorCnt @8 :UInt8; + transmitErrorCnt @9 :UInt8; + totalErrorCnt @10 :UInt32; + totalTxLostCnt @11 :UInt32; + totalRxLostCnt @12 :UInt32; + totalTxCnt @13 :UInt32; + totalRxCnt @14 :UInt32; + totalFwdCnt @15 :UInt32; + canSpeed @16 :UInt16; + canDataSpeed @17 :UInt16; + canfdEnabled @18 :Bool; + brsEnabled @19 :Bool; + canfdNonIso @20 :Bool; + + enum LecErrorCode { + noError @0; + stuffError @1; + formError @2; + ackError @3; + bit1Error @4; + bit0Error @5; + crcError @6; + noChange @7; + } + } } struct PeripheralState { @@ -478,9 +532,9 @@ struct PeripheralState { voltage @1 :UInt32; current @2 :UInt32; fanSpeedRpm @3 :UInt16; - usbPowerMode @4 :UsbPowerMode; - enum UsbPowerMode @0xa8883583b32c9877 { + usbPowerModeDEPRECATED @4 :UsbPowerModeDEPRECATED; + enum UsbPowerModeDEPRECATED @0xa8883583b32c9877 { none @0; client @1; cdp @2; @@ -538,6 +592,7 @@ struct LiveCalibrationData { # the direction of travel vector in device frame rpyCalib @7 :List(Float32); rpyCalibSpread @8 :List(Float32); + wideFromDeviceEuler @10 :List(Float32); warpMatrixDEPRECATED @0 :List(Float32); warpMatrix2DEPRECATED @5 :List(Float32); @@ -567,6 +622,8 @@ struct ControlsState @0x97ff69c53601abf1 { enabled @19 :Bool; active @36 :Bool; + experimentalMode @64 :Bool; + longControlState @30 :Car.CarControl.Actuators.LongControlState; vPid @2 :Float32; vTargetLead @3 :Float32; @@ -597,10 +654,12 @@ struct ControlsState @0x97ff69c53601abf1 { lateralControlState :union { indiState @52 :LateralINDIState; pidState @53 :LateralPIDState; - lqrState @55 :LateralLQRState; angleState @58 :LateralAngleState; debugState @59 :LateralDebugState; torqueState @60 :LateralTorqueState; + curvatureState @65 :LateralCurvatureState; + + lqrStateDEPRECATED @55 :LateralLQRState; } enum OpenpilotState @0xdbe58b96d2d1ac61 { @@ -608,7 +667,7 @@ struct ControlsState @0x97ff69c53601abf1 { preEnabled @1; enabled @2; softDisabling @3; - overriding @4; + overriding @4; # superset of overriding with steering or accelerator } enum AlertStatus { @@ -685,6 +744,18 @@ struct ControlsState @0x97ff69c53601abf1 { steeringAngleDesiredDeg @4 :Float32; } + struct LateralCurvatureState { + active @0 :Bool; + actualCurvature @1 :Float32; + desiredCurvature @2 :Float32; + error @3 :Float32; + p @4 :Float32; + i @5 :Float32; + f @6 :Float32; + output @7 :Float32; + saturated @8 :Bool; + } + struct LateralDebugState { active @0 :Bool; steeringAngleDeg @1 :Float32; @@ -753,6 +824,9 @@ struct ModelDataV2 { meta @12 :MetaData; + # Model perceived motion + temporalPose @21 :Pose; + # All SI units and in device frame struct XYZTData { x @0 :List(Float32); @@ -816,6 +890,13 @@ struct ModelDataV2 { brake4MetersPerSecondSquaredProbs @5 :List(Float32); brake5MetersPerSecondSquaredProbs @6 :List(Float32); } + + struct Pose { + trans @0 :List(Float32); # m/s in device frame + rot @1 :List(Float32); # rad/s in device frame + transStd @2 :List(Float32); # std m/s in device frame + rotStd @3 :List(Float32); # std rad/s in device frame + } } struct EncodeIndex { @@ -917,11 +998,11 @@ struct LongitudinalPlan @0xe00b5b3eba12876c { struct LateralPlan @0xe1e9318e2ae8b51e { modelMonoTime @31 :UInt64; - laneWidth @0 :Float32; - lProb @5 :Float32; - rProb @7 :Float32; + laneWidthDEPRECATED @0 :Float32; + lProbDEPRECATED @5 :Float32; + rProbDEPRECATED @7 :Float32; dPathPoints @20 :List(Float32); - dProb @21 :Float32; + dProbDEPRECATED @21 :Float32; mpcSolutionValid @9 :Bool; desire @17 :Desire; @@ -1086,16 +1167,16 @@ struct ProcLog { } struct GnssMeasurements { - ubloxMonoTime @0 :UInt64; + measTime @0 :UInt64; gpsWeek @1 :Int16; gpsTimeOfWeek @2 :Float64; correctedMeasurements @3 :List(CorrectedMeasurement); - positionECEF @4 :LiveLocationKalman.Measurement; - velocityECEF @5 :LiveLocationKalman.Measurement; - # Used for debugging: - positionFixECEF @6 :LiveLocationKalman.Measurement; + kalmanPositionECEF @4 :LiveLocationKalman.Measurement; + kalmanVelocityECEF @5 :LiveLocationKalman.Measurement; + positionECEF @6 :LiveLocationKalman.Measurement; + velocityECEF @7 :LiveLocationKalman.Measurement; # Todo sync this with timing pulse of ublox struct CorrectedMeasurement { @@ -1121,14 +1202,14 @@ struct GnssMeasurements { } enum ConstellationId { - # Satellite Constellation using the Ublox gnssid as index - gps @0; - sbas @1; - galileo @2; - beidou @3; - imes @4; - qznss @5; - glonass @6; + # Satellite Constellation using the Ublox gnssid as index + gps @0; + sbas @1; + galileo @2; + beidou @3; + imes @4; + qznss @5; + glonass @6; } enum EphemerisSourceType { @@ -1136,6 +1217,7 @@ struct GnssMeasurements { # Different ultra-rapid files: nasaUltraRapid @1; glonassIacUltraRapid @2; + qcom @3; } } @@ -1329,7 +1411,7 @@ struct QcomGnss @0xde94674b07ae51c1 { unknown3 @3; unknown4 @4; unknown5 @5; - unknown6 @6; + sbas @6; } enum SVObservationState @0xe81e829a0d6c83e9 { @@ -1752,6 +1834,22 @@ struct LiveParametersData { roll @14 :Float32; } +struct LiveTorqueParametersData { + liveValid @0 :Bool; + latAccelFactorRaw @1 :Float32; + latAccelOffsetRaw @2 :Float32; + frictionCoefficientRaw @3 :Float32; + latAccelFactorFiltered @4 :Float32; + latAccelOffsetFiltered @5 :Float32; + frictionCoefficientFiltered @6 :Float32; + totalBucketPoints @7 :Float32; + decay @8 :Float32; + maxResets @9 :Float32; + points @10 :List(List(Float32)); + version @11 :Int32; + useParams @12 :Bool; +} + struct LiveMapDataDEPRECATED { speedLimitValid @0 :Bool; speedLimit @1 :Float32; @@ -1779,6 +1877,8 @@ struct CameraOdometry { rot @1 :List(Float32); # rad/s in device frame transStd @2 :List(Float32); # std m/s in device frame rotStd @3 :List(Float32); # std rad/s in device frame + wideFromDeviceEuler @6 :List(Float32); + wideFromDeviceEulerStd @7 :List(Float32); } struct Sentinel { @@ -1792,6 +1892,10 @@ struct Sentinel { signal @1 :Int32; } +struct UIDebug { + drawTimeMillis @0 :Float32; +} + struct ManagerState { processes @0 :List(ProcessState); @@ -1861,6 +1965,30 @@ struct NavRoute { } } +struct MapRenderState { + locationMonoTime @0 :UInt64; + renderTime @1 :Float32; + frameId @2: UInt32; +} + +struct NavModelData { + frameId @0 :UInt32; + modelExecutionTime @1 :Float32; + dspExecutionTime @2 :Float32; + features @3 :List(Float32); + # predicted future position + position @4 :XYData; + desirePrediction @5 :List(Float32); + + # All SI units and in device frame + struct XYData { + x @0 :List(Float32); + y @1 :List(Float32); + xStd @2 :List(Float32); + yStd @3 :List(Float32); + } +} + struct EncodeData { idx @0 :EncodeIndex; data @1 :Data; @@ -1871,6 +1999,15 @@ struct EncodeData { struct UserFlag { } +struct Microphone { + soundPressure @0 :Float32; + + # uncalibrated, A-weighted + soundPressureWeighted @3 :Float32; + soundPressureWeightedDb @1 :Float32; + filteredSoundPressureWeightedDb @2 :Float32; +} + struct Event { logMonoTime @0 :UInt64; # nanoseconds valid @67 :Bool = true; @@ -1887,7 +2024,13 @@ struct Event { gpsNMEA @3 :GPSNMEAData; can @5 :List(CanData); controlsState @7 :ControlsState; - sensorEvents @11 :List(SensorEventData); + gyroscope @99 :SensorEventData; + gyroscope2 @100 :SensorEventData; + accelerometer @98 :SensorEventData; + accelerometer2 @101 :SensorEventData; + magnetometer @95 :SensorEventData; + lightSensor @96 :SensorEventData; + temperatureSensor @97 :SensorEventData; pandaStates @81 :List(PandaState); peripheralState @80 :PeripheralState; radarState @13 :RadarState; @@ -1905,6 +2048,7 @@ struct Event { gpsLocation @21 :GpsLocationData; gnssMeasurements @91 :GnssMeasurements; liveParameters @61 :LiveParametersData; + liveTorqueParameters @94 :LiveTorqueParametersData; cameraOdometry @63 :CameraOdometry; thumbnail @66: Thumbnail; carEvents @68: List(Car.CarEvent); @@ -1913,6 +2057,7 @@ struct Event { liveLocationKalman @72 :LiveLocationKalman; modelV2 @75 :ModelDataV2; driverStateV2 @92 :DriverStateV2; + navModel @104 :NavModelData; # camera stuff, each camera state has a matching encode idx roadCameraState @2 :FrameData; @@ -1923,6 +2068,9 @@ struct Event { wideRoadEncodeIdx @77 :EncodeIndex; qRoadEncodeIdx @90 :EncodeIndex; + # microphone data + microphone @103 :Microphone; + # systems stuff androidLog @20 :AndroidLogEntry; managerState @78 :ManagerState; @@ -1937,9 +2085,11 @@ struct Event { navInstruction @82 :NavInstruction; navRoute @83 :NavRoute; navThumbnail @84: Thumbnail; + mapRenderState @105: MapRenderState; - # user flags + # UI services userFlag @93 :UserFlag; + uiDebug @102 :UIDebug; # *********** debug *********** testJoystick @52 :Joystick; @@ -1985,5 +2135,6 @@ struct Event { uiLayoutStateDEPRECATED @57 :Legacy.UiLayoutState; pandaStateDEPRECATED @12 :PandaState; driverStateDEPRECATED @59 :DriverStateDEPRECATED; + sensorEventsDEPRECATED @11 :List(SensorEventData); } } diff --git a/messaging/messaging.h b/messaging/messaging.h index 51ddb7af2..5a69dde64 100644 --- a/messaging/messaging.h +++ b/messaging/messaging.h @@ -3,6 +3,8 @@ #include #include #include +#include + #include #include "../gen/cpp/log.capnp.h" diff --git a/messaging/msgq.cc b/messaging/msgq.cc index f527a5656..4386acfb7 100644 --- a/messaging/msgq.cc +++ b/messaging/msgq.cc @@ -320,9 +320,11 @@ int msgq_msg_ready(msgq_queue_t * q){ uint32_t read_cycles, read_pointer; UNPACK64(read_cycles, read_pointer, *q->read_pointers[id]); + UNUSED(read_cycles); uint32_t write_cycles, write_pointer; UNPACK64(write_cycles, write_pointer, *q->write_pointer); + UNUSED(write_cycles); // Check if new message is available return (read_pointer != write_pointer); @@ -350,6 +352,7 @@ int msgq_msg_recv(msgq_msg_t * msg, msgq_queue_t * q){ uint32_t write_cycles, write_pointer; UNPACK64(write_cycles, write_pointer, *q->write_pointer); + UNUSED(write_cycles); char * p = q->data + read_pointer; diff --git a/messaging/msgq.h b/messaging/msgq.h index 90a20acdd..86e9d1938 100644 --- a/messaging/msgq.h +++ b/messaging/msgq.h @@ -5,9 +5,10 @@ #include #define DEFAULT_SEGMENT_SIZE (10 * 1024 * 1024) -#define NUM_READERS 10 +#define NUM_READERS 12 #define ALIGN(n) ((n + (8 - 1)) & -8) +#define UNUSED(x) (void)x #define UNPACK64(higher, lower, input) do {uint64_t tmp = input; higher = tmp >> 32; lower = tmp & 0xFFFFFFFF;} while (0) #define PACK64(output, higher, lower) output = ((uint64_t)higher << 32 ) | ((uint64_t)lower & 0xFFFFFFFF) diff --git a/messaging/tests/test_services.py b/messaging/tests/test_services.py index 23943e7b6..f24fa9014 100755 --- a/messaging/tests/test_services.py +++ b/messaging/tests/test_services.py @@ -15,7 +15,7 @@ def test_services(self, s): service = service_list[s] self.assertTrue(service.port != RESERVED_PORT) self.assertTrue(service.port >= STARTING_PORT) - self.assertTrue(service.frequency <= 100) + self.assertTrue(service.frequency <= 104) def test_no_duplicate_port(self): ports = {} diff --git a/services.py b/services.py index a64d8ca8b..d0904f5b6 100755 --- a/services.py +++ b/services.py @@ -21,7 +21,13 @@ def __init__(self, port: int, should_log: bool, frequency: float, decimation: Op services = { # service: (should_log, frequency, qlog decimation (optional)) # note: the "EncodeIdx" packets will still be in the log - "sensorEvents": (True, 100., 100), + "gyroscope": (True, 104., 104), + "gyroscope2": (True, 100., 100), + "accelerometer": (True, 104., 104), + "accelerometer2": (True, 100., 100), + "magnetometer": (True, 100., 100), + "lightSensor": (True, 100., 100), + "temperatureSensor": (True, 100., 100), "gpsNMEA": (True, 9.), "deviceState": (True, 2., 1), "can": (True, 100.), @@ -35,6 +41,7 @@ def __init__(self, port: int, should_log: bool, frequency: float, decimation: Op "logMessage": (True, 0.), "errorLogMessage": (True, 0., 1), "liveCalibration": (True, 4., 4), + "liveTorqueParameters": (True, 4., 1), "androidLog": (True, 0.), "carState": (True, 100., 10), "carControl": (True, 100., 10), @@ -67,10 +74,14 @@ def __init__(self, port: int, should_log: bool, frequency: float, decimation: Op "navInstruction": (True, 1., 10), "navRoute": (True, 0.), "navThumbnail": (True, 0.), + "navModel": (True, 2., 4.), + "mapRenderState": (True, 2., 1.), "qRoadEncodeIdx": (False, 20.), "userFlag": (True, 0., 1), + "microphone": (True, 10., 10), # debug + "uiDebug": (True, 0., 1), "testJoystick": (True, 0.), "roadEncodeData": (False, 20.), "driverEncodeData": (False, 20.),