rusEFI
The most advanced open source ECU
Loading...
Searching...
No Matches
Functions | Variables
can_rx.cpp File Reference

Detailed Description

CAN reception handling. This file handles multiplexing incoming CAN frames as appropriate to the subsystems that consume them.

Date
Mar 19, 2020
Author
Matthew Kennedy, (c) 2020

Definition in file can_rx.cpp.

Functions

static void printPacket (const size_t busIndex, const CANRxFrame &rx)
 
void serviceCanSubscribers (const size_t busIndex, const CANRxFrame &frame, efitick_t nowNt)
 
void registerCanListener (CanListener &listener)
 
void registerCanSensor (CanSensorBase &sensor)
 
uint32_t getFourBytesLsb (const CANRxFrame &frame, int offset)
 
uint16_t getTwoBytesLsb (const CANRxFrame &frame, int offset)
 
uint16_t getTwoBytesMsb (const CANRxFrame &frame, int offset)
 
static int16_t getShiftedLSB_intel (const CANRxFrame &frame, int offset)
 
static void processCanRxImu_BoschM5_10_YawY (const CANRxFrame &frame)
 
static void processCanRxImu_BoschM5_10_RollX (const CANRxFrame &frame)
 
static void processCanRxImu_BoschM5_10_Z (const CANRxFrame &frame)
 
static void processCanRxImu (const CANRxFrame &frame)
 
void boardProcessCanRxMessage (const size_t, const CANRxFrame &, efitick_t)
 
void processCanRxMessage (const size_t busIndex, const CANRxFrame &frame, efitick_t nowNt)
 

Variables

static CanListenerTailSentinel tailSentinel
 
CanListenercanListeners_head = &tailSentinel
 
bool verboseRxCan
 
std::optional< board_can_rx_typecustom_board_can_rx
 

Function Documentation

◆ boardProcessCanRxMessage()

void boardProcessCanRxMessage ( const size_t  ,
const CANRxFrame ,
efitick_t   
)

Definition at line 196 of file can_rx.cpp.

196 {
197 // this is here to indicate that migration is required
198 // todo: remove in 2026
199}

◆ getFourBytesLsb()

uint32_t getFourBytesLsb ( const CANRxFrame frame,
int  offset 
)

Definition at line 119 of file can_rx.cpp.

119 {
120 return (frame.data8[offset + 3] << 24) +
121 (frame.data8[offset + 2] << 16) +
122 (frame.data8[offset + 1] << 8) +
123 frame.data8[offset];
124}
uint8_t data8[8]
Frame data.
Definition can_mocks.h:55
uint16_t offset
Definition tunerstudio.h:0

Referenced by processCanRequestCalibration().

Here is the caller graph for this function:

◆ getShiftedLSB_intel()

static int16_t getShiftedLSB_intel ( const CANRxFrame frame,
int  offset 
)
static

Definition at line 134 of file can_rx.cpp.

134 {
135 return getTwoBytesLsb(frame, offset) - 0x8000;
136}
uint16_t getTwoBytesLsb(const CANRxFrame &frame, int offset)
Definition can_rx.cpp:126

Referenced by processCanRxImu_BoschM5_10_RollX(), processCanRxImu_BoschM5_10_YawY(), and processCanRxImu_BoschM5_10_Z().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getTwoBytesLsb()

uint16_t getTwoBytesLsb ( const CANRxFrame frame,
int  offset 
)

Definition at line 126 of file can_rx.cpp.

126 {
127 return (frame.data8[offset + 1] << 8) + frame.data8[offset];
128}

Referenced by getShiftedLSB_intel(), processBMW_e46(), processBMW_e90(), and processCanUserControl().

Here is the caller graph for this function:

◆ getTwoBytesMsb()

uint16_t getTwoBytesMsb ( const CANRxFrame frame,
int  offset 
)

Definition at line 130 of file can_rx.cpp.

130 {
131 return (frame.data8[offset] << 8) + frame.data8[offset + 1];
132}

Referenced by processNissan(), and processNissanSecondVss().

Here is the caller graph for this function:

◆ printPacket()

static void printPacket ( const size_t  busIndex,
const CANRxFrame rx 
)
static

this build-in CAN sniffer is very basic but that's our CAN sniffer

Definition at line 29 of file can_rx.cpp.

29 {
30 // only print info if we're in can debug mode
31
32 int id = CAN_ID(rx);
33
34 if (CAN_ISX(rx)) {
35 // print extended IDs in hex only
36 efiPrintf("CAN%d RX: ID %07x DLC %d: %02x %02x %02x %02x %02x %02x %02x %02x",
37 busIndex + 1,
38 id,
39 rx.DLC,
40 rx.data8[0], rx.data8[1], rx.data8[2], rx.data8[3],
41 rx.data8[4], rx.data8[5], rx.data8[6], rx.data8[7]);
42 } else {
43 // internet people use both hex and decimal to discuss packed IDs, for usability it's better to print both right here
44 efiPrintf("CAN%d RX: ID %03x(%d) DLC %d: %02x %02x %02x %02x %02x %02x %02x %02x",
45 busIndex + 1,
46 id, id, // once in hex, once in dec
47 rx.DLC,
48 rx.data8[0], rx.data8[1], rx.data8[2], rx.data8[3],
49 rx.data8[4], rx.data8[5], rx.data8[6], rx.data8[7]);
50 }
51}
uint8_t DLC
Data length.
Definition can_mocks.h:42

Referenced by processCanRxMessage().

Here is the caller graph for this function:

◆ processCanRxImu()

static void processCanRxImu ( const CANRxFrame frame)
static

Definition at line 160 of file can_rx.cpp.

160 {
161/*
162 if (CAN_SID(frame) == 0x130) {
163 float a = getShiftedLSB_intel(frame, 0);
164 float b = getShiftedLSB_intel(frame, 4);
165 efiPrintf("CAN_rx 130 %f %f", a, b);
166 }
167
168 if (engineConfiguration->imuType == IMU_VAG) {
169 if (CAN_SID(frame) == VAG_YAW_RATE_G_LAT) {
170 efiPrintf("CAN_rx VAG_YAW_RATE_G_LAT");
171 } else if (CAN_SID(frame) == VAG_YAW_ACCEL_G_LONG) {
172 efiPrintf("CAN_rx VAG_YAW_ACCEL_G_LONG");
173 }
174 }
175 */
176
177 if (engineConfiguration->imuType == IMU_MM5_10) {
178 if (CAN_SID(frame) == MM5_10_YAW_Y) {
180 } else if (CAN_SID(frame) == MM5_10_ROLL_X) {
182 } else if (CAN_SID(frame) == MM5_10_Z) {
184 }
185 } else if (engineConfiguration->imuType == IMU_TYPE_MB_A0065422618) {
186 if (CAN_SID(frame) == MM5_10_MB_YAW_Y_CANID) {
188 } else if (CAN_SID(frame) == MM5_10_MB_ROLL_X_CANID) {
190 }
191 }
192}
static void processCanRxImu_BoschM5_10_RollX(const CANRxFrame &frame)
Definition can_rx.cpp:147
static void processCanRxImu_BoschM5_10_YawY(const CANRxFrame &frame)
Definition can_rx.cpp:138
static void processCanRxImu_BoschM5_10_Z(const CANRxFrame &frame)
Definition can_rx.cpp:154
static constexpr engine_configuration_s * engineConfiguration

Referenced by processCanRxMessage().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ processCanRxImu_BoschM5_10_RollX()

static void processCanRxImu_BoschM5_10_RollX ( const CANRxFrame frame)
static

Definition at line 147 of file can_rx.cpp.

147 {
148 float accX = getShiftedLSB_intel(frame, 4);
149 efiPrintf("CAN_rx MM5_10_ROLL_X %f", accX);
150
151 engine->sensors.accelerometer.lon = accX * MM5_10_ACC_QUANT;
152}
static int16_t getShiftedLSB_intel(const CANRxFrame &frame, int offset)
Definition can_rx.cpp:134
SensorsState sensors
Definition engine.h:353
static EngineAccessor engine
Definition engine.h:413
Accelerometer accelerometer

Referenced by processCanRxImu().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ processCanRxImu_BoschM5_10_YawY()

static void processCanRxImu_BoschM5_10_YawY ( const CANRxFrame frame)
static

Definition at line 138 of file can_rx.cpp.

138 {
139 float yaw = getShiftedLSB_intel(frame, 0);
140 float accY = getShiftedLSB_intel(frame, 4);
141
142 efiPrintf("CAN_rx MM5_10_YAW_Y %f %f", yaw, accY);
143 engine->sensors.accelerometer.yawRate = yaw * MM5_10_RATE_QUANT;
144 engine->sensors.accelerometer.lat = accY * MM5_10_ACC_QUANT;
145}

Referenced by processCanRxImu().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ processCanRxImu_BoschM5_10_Z()

static void processCanRxImu_BoschM5_10_Z ( const CANRxFrame frame)
static

Definition at line 154 of file can_rx.cpp.

154 {
155 float accZ = getShiftedLSB_intel(frame, 4);
156 efiPrintf("CAN_rx MM5_10_Z %f", accZ);
157 engine->sensors.accelerometer.vert = accZ * MM5_10_ACC_QUANT;
158}

Referenced by processCanRxImu().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ processCanRxMessage()

void processCanRxMessage ( const size_t  busIndex,
const CANRxFrame frame,
efitick_t  nowNt 
)

Definition at line 203 of file can_rx.cpp.

203 {
204 if ((engineConfiguration->verboseCan && busIndex == 0) || verboseRxCan) {
205 printPacket(busIndex, frame);
206 } else if (engineConfiguration->verboseCan2 && busIndex == 1) {
207 printPacket(busIndex, frame);
208 }
209
210 if (custom_board_can_rx.has_value()) {
211 custom_board_can_rx.value()(busIndex, frame, nowNt);
212 }
213
214 // see AemXSeriesWideband as an example of CanSensorBase/CanListener
215 serviceCanSubscribers(busIndex, frame, nowNt);
216
217 // todo: convert to CanListener or not?
218 //Vss is configurable, should we handle it here:
219 processCanRxVss(frame, nowNt);
220
222 // todo: convert to CanListener or not?
223 processCanRxImu(frame);
224 }
225
226/*
227static Timer dashAliveTimer;
228
229 if (CAN_EID(frame) == (int)bench_test_packet_ids_e::DASH_ALIVE) {
230 // todo: add an indicator that dash is connected?
231 dashAliveTimer.reset();
232 }
233*/
234
237
238 processLuaCan(busIndex, frame);
239
240 {
241 obdOnCanPacketRx(frame, busIndex);
242 }
243
244#if EFI_ENGINE_CONTROL
245 if (CAN_EID(frame) == GDI4_BASE_ADDRESS && frame.data8[7] == GDI4_MAGIC) {
246// efiPrintf("CAN GDI4 says hi");
248 }
249#endif // EFI_ENGINE_CONTROL
250
251 handleWidebandCan(busIndex, frame);
252#if EFI_USE_OPENBLT
253#include "openblt/efi_blt_ids.h"
254 if ((CAN_SID(frame) == BOOT_COM_CAN_RX_MSG_ID) && (frame.DLC == 2)) {
255 /* TODO: gracefull shutdown? */
256 if (((busIndex == 0) && (engineConfiguration->canOpenBLT)) ||
257 ((busIndex == 1) && (engineConfiguration->can2OpenBLT))) {
259 }
260 }
261#endif
262}
void jump_to_openblt()
void processCanEcuControl(const CANRxFrame &frame)
void processCanQcBenchTest(const CANRxFrame &frame)
std::optional< board_can_rx_type > custom_board_can_rx
Definition can_rx.cpp:201
static void processCanRxImu(const CANRxFrame &frame)
Definition can_rx.cpp:160
static void printPacket(const size_t busIndex, const CANRxFrame &rx)
Definition can_rx.cpp:29
bool verboseRxCan
Definition settings.cpp:364
void serviceCanSubscribers(const size_t busIndex, const CANRxFrame &frame, efitick_t nowNt)
Definition can_rx.cpp:71
void processCanRxVss(const CANRxFrame &frame, efitick_t nowNt)
Definition can_vss.cpp:177
Timer externalGdiCanBusComms
LimpManager * getLimpManager()
Definition engine.cpp:596
void processLuaCan(const size_t busIndex, const CANRxFrame &frame)
void obdOnCanPacketRx(const CANRxFrame &rx, size_t busIndex)
Definition obd2.cpp:210
void handleWidebandCan(const size_t busIndex, const CANRxFrame &frame)
Here is the call graph for this function:

◆ registerCanListener()

void registerCanListener ( CanListener listener)

Definition at line 84 of file can_rx.cpp.

84 {
85 // If the listener already has a next, it's already registered
86 if (!listener.hasNext()) {
89 }
90}
CanListener * canListeners_head
Definition can_rx.cpp:69
bool hasNext() const
void setNext(CanListener *next)
static CanTsListener listener

Referenced by CanStreamer::init(), initCanGpioMsiobox(), and registerCanSensor().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ registerCanSensor()

void registerCanSensor ( CanSensorBase sensor)

Definition at line 92 of file can_rx.cpp.

92 {
95}
void registerCanListener(CanListener &listener)
Definition can_rx.cpp:84
bool Register()
Definition sensor.cpp:131
static Lps25Sensor sensor(device)

Referenced by initCanSensors(), initEgt(), and initLambda().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ serviceCanSubscribers()

void serviceCanSubscribers ( const size_t  busIndex,
const CANRxFrame frame,
efitick_t  nowNt 
)

Definition at line 71 of file can_rx.cpp.

71 {
73 size_t iterationValidationCounter = 0;
74
75 while (current) {
76 current = current->processFrame(busIndex, frame, nowNt);
77 if (iterationValidationCounter++ > 239) {
78 criticalError("forever loop canListeners_head");
79 return;
80 }
81 }
82}
CanListener * processFrame(const size_t busIndex, const CANRxFrame &frame, efitick_t nowNt)

Referenced by processCanRxMessage().

Here is the call graph for this function:
Here is the caller graph for this function:

Variable Documentation

◆ canListeners_head

CanListener* canListeners_head = &tailSentinel

Definition at line 69 of file can_rx.cpp.

Referenced by CanWrite::PeriodicTask(), registerCanListener(), and serviceCanSubscribers().

◆ custom_board_can_rx

std::optional<board_can_rx_type> custom_board_can_rx

Definition at line 201 of file can_rx.cpp.

Referenced by processCanRxMessage().

◆ tailSentinel

CanListenerTailSentinel tailSentinel
static

Definition at line 68 of file can_rx.cpp.

◆ verboseRxCan

bool verboseRxCan
extern

Definition at line 364 of file settings.cpp.

Referenced by enableOrDisable(), and processCanRxMessage().

Go to the source code of this file.