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

void printCANRxFrame (const size_t busIndex, const CANRxFrame &rx)
 
void serviceCanSubscribers (const size_t busIndex, const CANRxFrame &frame, efitick_t nowNt)
 
void registerCanListener (CanListener &listener)
 
void unregisterCanListener (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 220 of file can_rx.cpp.

220 {
221 // this is here to indicate that migration is required
222 // todo: remove in 2026
223}

◆ getFourBytesLsb()

uint32_t getFourBytesLsb ( const CANRxFrame frame,
int  offset 
)

Definition at line 143 of file can_rx.cpp.

143 {
144 return (frame.data8[offset + 3] << 24) +
145 (frame.data8[offset + 2] << 16) +
146 (frame.data8[offset + 1] << 8) +
147 frame.data8[offset];
148}
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 158 of file can_rx.cpp.

158 {
159 return getTwoBytesLsb(frame, offset) - 0x8000;
160}
uint16_t getTwoBytesLsb(const CANRxFrame &frame, int offset)
Definition can_rx.cpp:150

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 150 of file can_rx.cpp.

150 {
151 return (frame.data8[offset + 1] << 8) + frame.data8[offset];
152}

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 154 of file can_rx.cpp.

154 {
155 return (frame.data8[offset] << 8) + frame.data8[offset + 1];
156}

Referenced by processNissan(), and processNissanSecondVss().

Here is the caller graph for this function:

◆ printCANRxFrame()

void printCANRxFrame ( const size_t  busIndex,
const CANRxFrame rx 
)

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(), IsoTpRx::readTimeout(), and CanStreamerState::receiveFrame().

Here is the caller graph for this function:

◆ processCanRxImu()

static void processCanRxImu ( const CANRxFrame frame)
static

Definition at line 184 of file can_rx.cpp.

184 {
185/*
186 if (CAN_SID(frame) == 0x130) {
187 float a = getShiftedLSB_intel(frame, 0);
188 float b = getShiftedLSB_intel(frame, 4);
189 efiPrintf("CAN_rx 130 %f %f", a, b);
190 }
191
192 if (engineConfiguration->imuType == IMU_VAG) {
193 if (CAN_SID(frame) == VAG_YAW_RATE_G_LAT) {
194 efiPrintf("CAN_rx VAG_YAW_RATE_G_LAT");
195 } else if (CAN_SID(frame) == VAG_YAW_ACCEL_G_LONG) {
196 efiPrintf("CAN_rx VAG_YAW_ACCEL_G_LONG");
197 }
198 }
199 */
200
201 if (engineConfiguration->imuType == IMU_MM5_10) {
202 if (CAN_SID(frame) == MM5_10_YAW_Y) {
204 } else if (CAN_SID(frame) == MM5_10_ROLL_X) {
206 } else if (CAN_SID(frame) == MM5_10_Z) {
208 }
209 } else if (engineConfiguration->imuType == IMU_TYPE_MB_A0065422618) {
210 if (CAN_SID(frame) == MM5_10_MB_YAW_Y_CANID) {
212 } else if (CAN_SID(frame) == MM5_10_MB_ROLL_X_CANID) {
214 }
215 }
216}
static void processCanRxImu_BoschM5_10_RollX(const CANRxFrame &frame)
Definition can_rx.cpp:171
static void processCanRxImu_BoschM5_10_YawY(const CANRxFrame &frame)
Definition can_rx.cpp:162
static void processCanRxImu_BoschM5_10_Z(const CANRxFrame &frame)
Definition can_rx.cpp:178
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 171 of file can_rx.cpp.

171 {
172 float accX = getShiftedLSB_intel(frame, 4);
173 efiPrintf("CAN_rx MM5_10_ROLL_X %f", accX);
174
175 engine->sensors.accelerometer.lon = accX * MM5_10_ACC_QUANT;
176}
static int16_t getShiftedLSB_intel(const CANRxFrame &frame, int offset)
Definition can_rx.cpp:158
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 162 of file can_rx.cpp.

162 {
163 float yaw = getShiftedLSB_intel(frame, 0);
164 float accY = getShiftedLSB_intel(frame, 4);
165
166 efiPrintf("CAN_rx MM5_10_YAW_Y %f %f", yaw, accY);
167 engine->sensors.accelerometer.yawRate = yaw * MM5_10_RATE_QUANT;
168 engine->sensors.accelerometer.lat = accY * MM5_10_ACC_QUANT;
169}

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 178 of file can_rx.cpp.

178 {
179 float accZ = getShiftedLSB_intel(frame, 4);
180 efiPrintf("CAN_rx MM5_10_Z %f", accZ);
181 engine->sensors.accelerometer.vert = accZ * MM5_10_ACC_QUANT;
182}

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 227 of file can_rx.cpp.

227 {
228 if (verboseRxCan ||
229 (engineConfiguration->verboseCan && busIndex == 0) ||
230 (engineConfiguration->verboseCan2 && busIndex == 1) ||
231#if (EFI_CAN_BUS_COUNT >= 3)
232 (engineConfiguration->verboseCan3 && busIndex == 2) ||
233#endif
234 0) {
235 printCANRxFrame(busIndex, frame);
236 }
237
238 // TODO use call_board_override
239 if (custom_board_can_rx.has_value()) {
240 custom_board_can_rx.value()(busIndex, frame, nowNt);
241 }
242
243 // see AemXSeriesWideband as an example of CanSensorBase/CanListener
244 serviceCanSubscribers(busIndex, frame, nowNt);
245
246 // todo: convert to CanListener or not?
247 //Vss is configurable, should we handle it here:
248 processCanRxVss(frame, nowNt);
249
251 // todo: convert to CanListener or not?
252 processCanRxImu(frame);
253 }
254
255/*
256static Timer dashAliveTimer;
257
258 if (CAN_EID(frame) == (int)bench_test_packet_ids_e::DASH_ALIVE) {
259 // todo: add an indicator that dash is connected?
260 dashAliveTimer.reset();
261 }
262*/
263
266
267 processLuaCan(busIndex, frame);
268
269 {
270 obdOnCanPacketRx(frame, busIndex);
271 }
272
273#if EFI_ENGINE_CONTROL
274 if (CAN_EID(frame) == GDI4_BASE_ADDRESS && frame.data8[7] == GDI4_MAGIC) {
275// efiPrintf("CAN GDI4 says hi");
277 }
278#endif // EFI_ENGINE_CONTROL
279
280 handleWidebandCan(busIndex, frame);
281#if EFI_USE_OPENBLT
282#include "openblt/efi_blt_ids.h"
283 if ((CAN_SID(frame) == BOOT_COM_CAN_RX_MSG_ID) && (frame.DLC == 2)) {
284 /* TODO: gracefull shutdown? */
285 if (((busIndex == 0) && (engineConfiguration->canOpenBLT)) ||
286 ((busIndex == 1) && (engineConfiguration->can2OpenBLT))) {
288 }
289 }
290#endif
291}
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:225
static void processCanRxImu(const CANRxFrame &frame)
Definition can_rx.cpp:184
bool verboseRxCan
Definition settings.cpp:364
void printCANRxFrame(const size_t busIndex, const CANRxFrame &rx)
Definition can_rx.cpp:29
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:608
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 86 of file can_rx.cpp.

86 {
87 // Do this under lock?
88
89 // If the listener already has a next, it's already registered
90 if (!listener.getNext()) {
91 listener.setNext(canListeners_head);
92 canListeners_head = &listener;
93 }
94}
CanListener * canListeners_head
Definition can_rx.cpp:69
CanListener * getNext() const
void setNext(CanListener *next)

Referenced by CanTransport::init(), initCanGpioMsiobox(), IsoTpRx::IsoTpRx(), 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 116 of file can_rx.cpp.

116 {
119}
void registerCanListener(CanListener &listener)
Definition can_rx.cpp:86
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:

◆ unregisterCanListener()

void unregisterCanListener ( CanListener listener)

Definition at line 96 of file can_rx.cpp.

96 {
97 // Do this under lock?
98
99 // listener is at head of list...
100 if (canListeners_head == &listener) {
101 canListeners_head = listener.getNext();
102 } else {
104
105 while (current->getNext() && (current->getNext() != &listener)) {
106 current = current->getNext();
107 }
108 if (current->getNext()) {
109 current->setNext(listener.getNext());
110 }
111 }
112
113 listener.setNext(nullptr);
114}

Referenced by IsoTpRx::~IsoTpRx().

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

Variable Documentation

◆ canListeners_head

CanListener* canListeners_head = &tailSentinel

◆ custom_board_can_rx

std::optional<board_can_rx_type> custom_board_can_rx

Definition at line 225 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.