openpilot v0.5.1 release (#315)
Merge commit '2cfdc676101c387524246f789c8429647069b827' into release2v0.5.1
commit
8f22f52235
97
README.md
97
README.md
|
@ -10,7 +10,7 @@ The openpilot codebase has been written to be concise and enable rapid prototypi
|
|||
Community
|
||||
------
|
||||
|
||||
openpilot is supported by [comma.ai](https://comma.ai/).
|
||||
openpilot is developed by [comma.ai](https://comma.ai/) and users like you.
|
||||
|
||||
We have a [Twitter you should follow](https://twitter.com/comma_ai).
|
||||
|
||||
|
@ -41,57 +41,62 @@ Install openpilot on a neo device by entering ``https://openpilot.comma.ai`` dur
|
|||
Supported Cars
|
||||
------
|
||||
|
||||
| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below |
|
||||
| ------- | ---------------------- | -------------------- | ------- | ------------ | -------------- | -------------- |
|
||||
| Acura | ILX 2016 | AcuraWatch Plus | Yes | Yes | 25mph* | 25mph |
|
||||
| Acura | ILX 2017 | AcuraWatch Plus | Yes | Yes | 25mph* | 25mph |
|
||||
| Acura | RDX 2018 | AcuraWatch Plus | Yes | Yes | 25mph* | 12mph |
|
||||
| GM | Volt 2017 | Driver Confidence II | Yes | Yes | 0mph | 0mph |
|
||||
| GM | Volt 2018 | Driver Confidence II | Yes | Yes | 0mph | 0mph |
|
||||
| Honda | Accord 2018 | All | Yes | Stock | 0mph | 3mph |
|
||||
| Honda | Civic 2016 | Honda Sensing | Yes | Yes | 0mph | 12mph |
|
||||
| Honda | Civic 2017 | Honda Sensing | Yes | Yes | 0mph | 12mph |
|
||||
| Honda | Civic 2017 *(Hatch)* | Honda Sensing | Yes | Stock | 0mph | 12mph |
|
||||
| Honda | Civic 2018 | Honda Sensing | Yes | Yes | 0mph | 12mph |
|
||||
| Honda | CR-V 2015 | Honda Sensing | Yes | Yes | 25mph* | 12mph |
|
||||
| Honda | CR-V 2016 | Honda Sensing | Yes | Yes | 25mph* | 12mph |
|
||||
| Honda | CR-V 2017 | Honda Sensing | Yes | Stock | 0mph | 12mph |
|
||||
| Honda | CR-V 2018 | Honda Sensing | Yes | Stock | 0mph | 12mph |
|
||||
| Honda | Odyssey 2017 | Honda Sensing | Yes | Yes | 25mph* | 12mph |
|
||||
| Honda | Odyssey 2018 | Honda Sensing | Yes | Yes | 25mph* | 12mph |
|
||||
| Honda | Pilot 2017 | Honda Sensing | Yes | Yes | 25mph* | 12mph |
|
||||
| Honda | Pilot 2018 | Honda Sensing | Yes | Yes | 25mph* | 12mph |
|
||||
| Honda | Ridgeline 2017 | Honda Sensing | Yes | Yes | 25mph* | 12mph |
|
||||
| Honda | Ridgeline 2018 | Honda Sensing | Yes | Yes | 25mph* | 12mph |
|
||||
| Lexus | RX Hybrid 2017 | All | Yes | Yes | 0mph | 0mph |
|
||||
| Lexus | RX Hybrid 2018 | All | Yes | Yes | 0mph | 0mph |
|
||||
| Toyota | Corolla 2017 | All | Yes | Yes | 20mph | 0mph |
|
||||
| Toyota | Corolla 2018 | All | Yes | Yes | 20mph | 0mph |
|
||||
| Toyota | Prius 2016 | TSS-P | Yes | Yes | 0mph | 0mph |
|
||||
| Toyota | Prius 2017 | All | Yes | Yes | 0mph | 0mph |
|
||||
| Toyota | Prius 2018 | All | Yes | Yes | 0mph | 0mph |
|
||||
| Toyota | Prius Prime 2017 | All | Yes | Yes | 0mph | 0mph |
|
||||
| Toyota | Prius Prime 2018 | All | Yes | Yes | 0mph | 0mph |
|
||||
| Toyota | Rav4 2016 | TSS-P | Yes | Yes | 20mph | 0mph |
|
||||
| Toyota | Rav4 2017 | All | Yes | Yes | 20mph | 0mph |
|
||||
| Toyota | Rav4 2018 | All | Yes | Yes | 20mph | 0mph |
|
||||
| Toyota | Rav4 Hybrid 2017 | All | Yes | Yes | 0mph | 0mph |
|
||||
| Toyota | Rav4 Hybrid 2018 | All | Yes | Yes | 0mph | 0mph |
|
||||
| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below |
|
||||
| ------- | ---------------------- | -------------------- | ------- | ------------ | -------------- | -------------- |
|
||||
| Acura | ILX 2016 | AcuraWatch Plus | Yes | Yes | 25mph<sup>1</sup>| 25mph |
|
||||
| Acura | ILX 2017 | AcuraWatch Plus | Yes | Yes | 25mph<sup>1</sup>| 25mph |
|
||||
| Acura | RDX 2018 | AcuraWatch Plus | Yes | Yes | 25mph<sup>1</sup>| 12mph |
|
||||
| GM<sup>3</sup>| Volt 2017 | Driver Confidence II | Yes | Yes | 0mph | 7mph |
|
||||
| GM<sup>3</sup>| Volt 2018 | Driver Confidence II | Yes | Yes | 0mph | 7mph |
|
||||
| Honda | Accord 2018 | All | Yes | Stock | 0mph | 3mph |
|
||||
| Honda | Civic 2016 | Honda Sensing | Yes | Yes | 0mph | 12mph |
|
||||
| Honda | Civic 2017 | Honda Sensing | Yes | Yes | 0mph | 12mph |
|
||||
| Honda | Civic 2017 *(Hatch)* | Honda Sensing | Yes | Stock | 0mph | 12mph |
|
||||
| Honda | Civic 2018 | Honda Sensing | Yes | Yes | 0mph | 12mph |
|
||||
| Honda | CR-V 2015 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph |
|
||||
| Honda | CR-V 2016 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph |
|
||||
| Honda | CR-V 2017 | Honda Sensing | Yes | Stock | 0mph | 12mph |
|
||||
| Honda | CR-V 2018 | Honda Sensing | Yes | Stock | 0mph | 12mph |
|
||||
| Honda | Odyssey 2017 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph |
|
||||
| Honda | Odyssey 2018 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph |
|
||||
| Honda | Pilot 2017 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph |
|
||||
| Honda | Pilot 2018 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph |
|
||||
| Honda | Ridgeline 2017 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph |
|
||||
| Honda | Ridgeline 2018 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph |
|
||||
| Lexus | RX Hybrid 2017 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph |
|
||||
| Lexus | RX Hybrid 2018 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph |
|
||||
| Toyota | Camry 2018<sup>4</sup> | All | Yes | Stock | 0mph<sup>5</sup> | 0mph |
|
||||
| Toyota | C-HR 2018<sup>4</sup> | All | Yes | Stock | 0mph | 0mph |
|
||||
| Toyota | Corolla 2017 | All | Yes | Yes<sup>2</sup>| 20mph | 0mph |
|
||||
| Toyota | Corolla 2018 | All | Yes | Yes<sup>2</sup>| 20mph | 0mph |
|
||||
| Toyota | Prius 2016 | TSS-P | Yes | Yes<sup>2</sup>| 0mph | 0mph |
|
||||
| Toyota | Prius 2017 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph |
|
||||
| Toyota | Prius 2018 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph |
|
||||
| Toyota | Prius Prime 2017 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph |
|
||||
| Toyota | Prius Prime 2018 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph |
|
||||
| Toyota | Rav4 2016 | TSS-P | Yes | Yes<sup>2</sup>| 20mph | 0mph |
|
||||
| Toyota | Rav4 2017 | All | Yes | Yes<sup>2</sup>| 20mph | 0mph |
|
||||
| Toyota | Rav4 2018 | All | Yes | Yes<sup>2</sup>| 20mph | 0mph |
|
||||
| Toyota | Rav4 Hybrid 2017 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph |
|
||||
| Toyota | Rav4 Hybrid 2018 | All | Yes | Yes<sup>2</sup>| 0mph | 0mph |
|
||||
|
||||
|
||||
*[Comma Pedal](https://community.comma.ai/wiki/index.php/Comma_Pedal) is used to provide stop-and-go capability to some of the openpilot-supported cars that don't currently support stop-and-go. Here is how to [build a Comma Pedal](https://medium.com/@jfrux/comma-pedal-building-with-macrofab-6328bea791e8). ***NOTE: The Comma Pedal is not officially supported by [comma.ai](https://comma.ai)***
|
||||
<sup>1</sup>[Comma Pedal](https://community.comma.ai/wiki/index.php/Comma_Pedal) is used to provide stop-and-go capability to some of the openpilot-supported cars that don't currently support stop-and-go. Here is how to [build a Comma Pedal](https://medium.com/@jfrux/comma-pedal-building-with-macrofab-6328bea791e8). ***NOTE: The Comma Pedal is not officially supported by [comma.ai](https://comma.ai)***
|
||||
<sup>2</sup>When disconnecting the Driver Support Unit (DSU), otherwise longitudinal control is stock ACC. For DSU locations, see [Toyota Wiki page](https://community.comma.ai/wiki/index.php/Toyota)
|
||||
<sup>3</sup>[GM installation guide](https://www.zoneos.com/volt.htm)
|
||||
<sup>4</sup>It needs an extra 120Ohm resistor ([pic1](https://i.imgur.com/CmdKtTP.jpg), [pic2](https://i.imgur.com/s2etUo6.jpg)) on bus 3 and giraffe switches set to 01X1 (11X1 for stock LKAS), where X depends on if you have the [comma power](https://comma.ai/shop/products/power/).
|
||||
<sup>5</sup>28mph for Camry 4CYL L, 4CYL LE and 4CYL SE which don't have Full-Speed Range Dynamic Radar Cruise Control.
|
||||
|
||||
Community Maintained Cars
|
||||
------
|
||||
|
||||
| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below |
|
||||
| ------- | -----------------------| -------------------- | ------- | ------------ | ----------- | ------------ |
|
||||
| Tesla | Model S 2012 | All | Yes | Not yet | Not applicable | 0mph |
|
||||
| Tesla | Model S 2013 | All | Yes | Not yet | Not applicable | 0mph |
|
||||
| Make | Model | Supported Package | Lateral | Longitudinal | No Accel Below | No Steer Below |
|
||||
| ------- | ---------------------- | -------------------- | ------- | ------------ | -------------- | -------------- |
|
||||
| Honda | Fit 2018 | Honda Sensing | Yes | Yes | 25mph<sup>1</sup>| 12mph |
|
||||
|
||||
[[Tesla Pull Request]](https://github.com/commaai/openpilot/pull/246)
|
||||
[[Honda Fit Pull Request]](https://github.com/commaai/openpilot/pull/266).
|
||||
|
||||
*Community Maintained Cars are not confirmed by comma.ai to meet our safety model. Be extra cautious using them.
|
||||
Community Maintained Cars are not confirmed by comma.ai to meet our safety model. Be extra cautious using them.
|
||||
|
||||
In Progress Cars
|
||||
------
|
||||
|
@ -107,7 +112,7 @@ How can I add support for my car?
|
|||
|
||||
If your car has adaptive cruise control and lane keep assist, you are in luck. Using a [panda](https://comma.ai/shop/products/panda-obd-ii-dongle/) and [cabana](https://community.comma.ai/cabana/), you can understand how to make your car drive by wire.
|
||||
|
||||
We've written a [porting guide](https://medium.com/@comma_ai/openpilot-port-guide-for-toyota-models-e5467f4b5fe6) for Toyota that might help you after you have the basics figured out.
|
||||
We've written guides for [Brand](https://medium.com/@comma_ai/how-to-write-a-car-port-for-openpilot-7ce0785eda84) and [Model](https://medium.com/@comma_ai/openpilot-port-guide-for-toyota-models-e5467f4b5fe6) ports. These guides might help you after you have the basics figured out.
|
||||
|
||||
- BMW, Audi, Volvo, and Mercedes all use [FlexRay](https://en.wikipedia.org/wiki/FlexRay) and are unlikely to be supported any time soon.
|
||||
- We put time into a Ford port, but the steering has a 10 second cutout limitation that makes it unusable.
|
||||
|
@ -174,7 +179,7 @@ Contributing
|
|||
------
|
||||
|
||||
We welcome both pull requests and issues on
|
||||
[github](http://github.com/commaai/openpilot). Bug fixes and new car support encouraged.
|
||||
[github](http://github.com/commaai/openpilot). Bug fixes and new car ports encouraged.
|
||||
|
||||
Want to get paid to work on openpilot? [comma.ai is hiring](https://comma.ai/jobs/)
|
||||
|
||||
|
|
|
@ -1,3 +1,10 @@
|
|||
Version 0.5.1 (2018-08-01)
|
||||
========================
|
||||
* Fix radar error on Civic sedan 2018
|
||||
* Improve thermal management logic
|
||||
* Alpha Toyota C-HR and Camry support!
|
||||
* Auto-switch Driver Monitoring to 3 min counter when inaccurate
|
||||
|
||||
Version 0.5 (2018-07-11)
|
||||
========================
|
||||
* Driver Monitoring (beta) option in settings!
|
||||
|
|
80
SAFETY.md
80
SAFETY.md
|
@ -6,7 +6,10 @@ Like other ACC and LKA systems, openpilot requires the driver to be alert and to
|
|||
pay attention at all times. We repeat, **driver alertness is necessary, but not
|
||||
sufficient, for openpilot to be used safely**.
|
||||
|
||||
Even with an attentive driver, we must make further efforts for the system to be
|
||||
In order to enforce driver alertness, openpilot includes a driver monitoring feature
|
||||
that alerts the driver when distracted.
|
||||
|
||||
However, even with an attentive driver, we must make further efforts for the system to be
|
||||
safe. We have designed openpilot with two other safety considerations.
|
||||
|
||||
1. The driver must always be capable to immediately retake manual control of the vehicle,
|
||||
|
@ -20,7 +23,7 @@ Following are details of the car specific safety implementations:
|
|||
Honda/Acura
|
||||
------
|
||||
|
||||
- While the system is engaged, gas, brake and steer limits are subject to the same limits used by
|
||||
- While the system is engaged, gas, brake and steer commands are subject to the same limits used by
|
||||
the stock system.
|
||||
|
||||
- Without an interceptor, the gas is controlled by the Powertrain Control Module (PCM).
|
||||
|
@ -28,16 +31,16 @@ Honda/Acura
|
|||
interceptor, the gas is clipped to 60%.
|
||||
|
||||
- The brake is controlled by the 0x1FA CAN message. This message allows full
|
||||
braking, although the board and the software clip it to 1/4th of the max.
|
||||
This is around .3g of braking.
|
||||
braking, although the panda firmware and openpilot clip it to 1/4th of the max.
|
||||
This is approximately 0.3g of braking.
|
||||
|
||||
- Steering is controlled by the 0xE4 CAN message. The Electronic Power Steering (EPS)
|
||||
controller in the car limits the torque to a very small amount, so regardless of the
|
||||
message, the controller cannot jerk the wheel.
|
||||
|
||||
- Brake and gas pedal pressed signals are contained in the 0x17C CAN message. A rising edge of
|
||||
either signal triggers a disengagement, which is enforced by the board and in software. The
|
||||
green led on the board signifies if the board is allowing control messages.
|
||||
either signals triggers a disengagement, which is enforced by the panda firmware and by openpilot. The
|
||||
white led on the panda signifies if the panda is allowing control messages.
|
||||
|
||||
- Honda CAN uses both a counter and a checksum to ensure integrity and prevent
|
||||
replay of the same message.
|
||||
|
@ -45,29 +48,62 @@ Honda/Acura
|
|||
Toyota/Lexus
|
||||
------
|
||||
|
||||
- While the system is engaged, gas, brake and steer limits are subject to the same limits used by
|
||||
- While the system is engaged, gas, brake and steer commands are subject to the same limits used by
|
||||
the stock system.
|
||||
|
||||
- With the stock Driving Support Unit (DSU) enabled, the acceleration is controlled
|
||||
by the stock system and is subject to the stock adaptive cruise control limits. Without the
|
||||
stock DSU connected, the acceleration command is controlled by the 0x343 CAN message and its
|
||||
value is limited by the board and the software to between .3g of deceleration and .15g of
|
||||
acceleration. The acceleration command is ignored by the Engine Control Module (ECM) while the
|
||||
cruise control system is disengaged.
|
||||
- With the stock Driving Support Unit (DSU) connected (or in DSU-less models like Camry and C-HR),
|
||||
the acceleration is controlled by the stock system and is subject to the stock adaptive cruise
|
||||
control limits. Without the stock DSU connected, the acceleration command is controlled by the
|
||||
0x343 CAN message and its value is limited between .3g of deceleration and .15g of acceleration
|
||||
by the panda firmware and by openpilot. The acceleration command is ignored by the Engine Control
|
||||
Module (ECM) while the cruise control system is disengaged.
|
||||
|
||||
- Steering torque is controlled through the 0x2E4 CAN message and it's limited by the board and in
|
||||
software to a value of -1500 and 1500. In addition, the vehicle EPS unit will not respond to
|
||||
commands outside these limits. A steering torque rate limit is enforced by the board and in
|
||||
software so that the commanded steering torque must rise from 0 to max value no faster than
|
||||
1.5s. Commanded steering torque is limited by the board and in software to be no more than 350
|
||||
- Steering torque is controlled through the 0x2E4 CAN message and it's limited by the panda firmware and by
|
||||
openpilot to a value between -1500 and 1500. In addition, the vehicle EPS unit will not respond to
|
||||
commands outside these limits. A steering torque rate limit is enforced by the panda firmware and by
|
||||
openpilot, so that the commanded steering torque must rise from 0 to max value no faster than
|
||||
1.5s. Commanded steering torque is limited by the panda firmware and by openpilot to be no more than 350
|
||||
units above the actual EPS generated motor torque to ensure limited differences between
|
||||
commanded and actual torques.
|
||||
|
||||
- Brake and gas pedal pressed signals are contained in the 0x224 and 0x1D2 CAN messages,
|
||||
respectively. A rising edge of either signal triggers a disengagement, which is enforced by the
|
||||
board and in software. Additionally, the cruise control system disengages on the rising edge of
|
||||
respectively. A rising edge of either signals triggers a disengagement, which is enforced by the
|
||||
panda firmware and by openpilot. Additionally, the cruise control system disengages on the rising edge of
|
||||
the brake pedal pressed signal.
|
||||
|
||||
- The cruise control system state is contained in the 0x1D2 message. No control messages are
|
||||
allowed if the cruise control system is not active. This is enforced by the software and the
|
||||
board. The green led on the board signifies if the board is allowing control messages.
|
||||
allowed if the cruise control system is not active. This is enforced by openpilot and the
|
||||
panda firmware. The white led on the panda signifies if the panda is allowing control messages.
|
||||
|
||||
GM/Chevrolet
|
||||
------
|
||||
|
||||
- While the system is engaged, gas, brake and steer commands are subject to the same limits used by
|
||||
the stock system.
|
||||
|
||||
- The gas and regen are controlled by the 0x2CB message and it's limited by the panda firmware and by
|
||||
openpilot to a value between 1404 and 3072. the minimum value correspond to a mild decel due to regen,
|
||||
while 3072 correspond to approximately 0.18g of acceleration from stop.
|
||||
|
||||
- The friction brakes are controlled by the 0x315 message and its value is limited by the panda firmware
|
||||
and openpilot to 350. This is approximately 0.3g of braking.
|
||||
|
||||
- Steering torque is controlled through the 0x180 CAN message and it's limited by the panda firmware and by
|
||||
openpilot to a value between -255 and 255. In addition, the vehicle EPS unit will not fault when
|
||||
commands outside these limits. A steering torque rate limit is enforced by the panda firmware and by
|
||||
openpilot, so that the commanded steering torque must rise from 0 to max value no faster than
|
||||
0.75s. Commanded steering torque is gradually limited by the panda firmware and by openpilot if the driver's
|
||||
torque exceeds 12 units in the opposite dicrection to ensure limited applied torque against the
|
||||
driver's will.
|
||||
|
||||
- Brake pedal and gas pedal potentiometer signals are contained in the 0xF1 and 0x1A1 CAN messages,
|
||||
respectively. A rising edge of either signals triggers a disengagement, which is enforced by the
|
||||
panda firmware and by openpilot. Additionally, the cruise control system disengages on the rising edge of
|
||||
the brake pedal pressed signal. The regen paddle pressed signal is in the 0xBD message. When the
|
||||
regen paddle is pressed, a disengagement is enforced by both the firmware and by openpilot.
|
||||
|
||||
- GM CAN uses both a counter and a checksum to ensure integrity and prevent
|
||||
replay of the same message.
|
||||
|
||||
**Extra note"**: comma.ai strongly discourages the use of openpilot forks with safety code either missing or
|
||||
not fully meeting the above requirements.
|
||||
|
|
Binary file not shown.
Binary file not shown.
|
@ -63,6 +63,11 @@ struct CarEvent @0x9b1657f34caf3ad3 {
|
|||
promptDriverDistracted @38;
|
||||
driverDistracted @39;
|
||||
geofence @40;
|
||||
driverMonitorOn @41;
|
||||
driverMonitorOff @42;
|
||||
preDriverUnresponsive @43;
|
||||
promptDriverUnresponsive @44;
|
||||
driverUnresponsive @45;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -302,6 +307,8 @@ struct CarParams {
|
|||
hondaBosch @5;
|
||||
ford @6;
|
||||
cadillac @7;
|
||||
hyundai @8;
|
||||
chrysler @9;
|
||||
}
|
||||
|
||||
# things about the car in the manual
|
||||
|
|
|
@ -21,6 +21,8 @@ struct Map(Key, Value) {
|
|||
|
||||
struct InitData {
|
||||
kernelArgs @0 :List(Text);
|
||||
kernelVersion @15 :Text;
|
||||
|
||||
gctx @1 :Text;
|
||||
dongleId @2 :Text;
|
||||
|
||||
|
@ -32,6 +34,7 @@ struct InitData {
|
|||
|
||||
androidBuildInfo @5 :AndroidBuildInfo;
|
||||
androidSensors @6 :List(AndroidSensor);
|
||||
androidProperties @16 :Map(Text, Text);
|
||||
chffrAndroidExtra @7 :ChffrAndroidExtra;
|
||||
iosBuildInfo @14 :IosBuildInfo;
|
||||
|
||||
|
@ -399,6 +402,7 @@ struct Live100Data {
|
|||
angleOffset @27 :Float32;
|
||||
gpsPlannerActive @40 :Bool;
|
||||
engageable @41 :Bool; # can OP be engaged?
|
||||
driverMonitoringOn @43 :Bool;
|
||||
|
||||
enum ControlState {
|
||||
disabled @0;
|
||||
|
@ -1533,6 +1537,13 @@ struct OrbKeyFrame {
|
|||
struct DriverMonitoring {
|
||||
frameId @0 :UInt32;
|
||||
descriptor @1 :List(Float32);
|
||||
std @2 :Float32;
|
||||
}
|
||||
|
||||
struct Boot {
|
||||
wallTimeNanos @0 :UInt64;
|
||||
lastKmsg @1 :Data;
|
||||
lastPmsg @2 :Data;
|
||||
}
|
||||
|
||||
struct Event {
|
||||
|
@ -1599,5 +1610,6 @@ struct Event {
|
|||
uiLayoutState @57 :UiLayoutState;
|
||||
orbFeaturesSummary @58 :OrbFeaturesSummary;
|
||||
driverMonitoring @59 :DriverMonitoring;
|
||||
boot @60 :Boot;
|
||||
}
|
||||
}
|
||||
|
|
|
@ -12,12 +12,14 @@ esq = 6.69437999014 * 0.001
|
|||
e1sq = 6.73949674228 * 0.001
|
||||
|
||||
|
||||
def geodetic2ecef(geodetic):
|
||||
def geodetic2ecef(geodetic, radians=False):
|
||||
geodetic = np.array(geodetic)
|
||||
input_shape = geodetic.shape
|
||||
geodetic = np.atleast_2d(geodetic)
|
||||
lat = (np.pi/180)*geodetic[:,0]
|
||||
lon = (np.pi/180)*geodetic[:,1]
|
||||
|
||||
ratio = 1.0 if radians else (np.pi / 180.0)
|
||||
lat = ratio*geodetic[:,0]
|
||||
lon = ratio*geodetic[:,1]
|
||||
alt = geodetic[:,2]
|
||||
|
||||
xi = np.sqrt(1 - esq * np.sin(lat)**2)
|
||||
|
@ -28,41 +30,41 @@ def geodetic2ecef(geodetic):
|
|||
return ecef.reshape(input_shape)
|
||||
|
||||
|
||||
def ecef2geodetic(ecef):
|
||||
def ecef2geodetic(ecef, radians=False):
|
||||
"""
|
||||
Convert ECEF coordinates to geodetic using ferrari's method
|
||||
"""
|
||||
def ferrari(x, y, z):
|
||||
# ferrari's method
|
||||
r = np.sqrt(x * x + y * y)
|
||||
Esq = a * a - b * b
|
||||
F = 54 * b * b * z * z
|
||||
G = r * r + (1 - esq) * z * z - esq * Esq
|
||||
C = (esq * esq * F * r * r) / (pow(G, 3))
|
||||
S = np.cbrt(1 + C + np.sqrt(C * C + 2 * C))
|
||||
P = F / (3 * pow((S + 1 / S + 1), 2) * G * G)
|
||||
Q = np.sqrt(1 + 2 * esq * esq * P)
|
||||
r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - \
|
||||
P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r)
|
||||
U = np.sqrt(pow((r - esq * r_0), 2) + z * z)
|
||||
V = np.sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z)
|
||||
Z_0 = b * b * z / (a * V)
|
||||
h = U * (1 - b * b / (a * V))
|
||||
lat = (180/np.pi)*np.arctan((z + e1sq * Z_0) / r)
|
||||
lon = (180/np.pi)*np.arctan2(y, x)
|
||||
return lat, lon, h
|
||||
|
||||
geodetic = []
|
||||
ecef = np.array(ecef)
|
||||
# Save shape and export column
|
||||
ecef = np.atleast_1d(ecef)
|
||||
input_shape = ecef.shape
|
||||
ecef = np.atleast_2d(ecef)
|
||||
for p in ecef:
|
||||
geodetic.append(ferrari(*p))
|
||||
geodetic = np.array(geodetic)
|
||||
x, y, z = ecef[:, 0], ecef[:, 1], ecef[:, 2]
|
||||
|
||||
ratio = 1.0 if radians else (180.0 / np.pi)
|
||||
|
||||
# Conver from ECEF to geodetic using Ferrari's methods
|
||||
# https://en.wikipedia.org/wiki/Geographic_coordinate_conversion#Ferrari.27s_solution
|
||||
r = np.sqrt(x * x + y * y)
|
||||
Esq = a * a - b * b
|
||||
F = 54 * b * b * z * z
|
||||
G = r * r + (1 - esq) * z * z - esq * Esq
|
||||
C = (esq * esq * F * r * r) / (pow(G, 3))
|
||||
S = np.cbrt(1 + C + np.sqrt(C * C + 2 * C))
|
||||
P = F / (3 * pow((S + 1 / S + 1), 2) * G * G)
|
||||
Q = np.sqrt(1 + 2 * esq * esq * P)
|
||||
r_0 = -(P * esq * r) / (1 + Q) + np.sqrt(0.5 * a * a*(1 + 1.0 / Q) - \
|
||||
P * (1 - esq) * z * z / (Q * (1 + Q)) - 0.5 * P * r * r)
|
||||
U = np.sqrt(pow((r - esq * r_0), 2) + z * z)
|
||||
V = np.sqrt(pow((r - esq * r_0), 2) + (1 - esq) * z * z)
|
||||
Z_0 = b * b * z / (a * V)
|
||||
h = U * (1 - b * b / (a * V))
|
||||
lat = ratio*np.arctan((z + e1sq * Z_0) / r)
|
||||
lon = ratio*np.arctan2(y, x)
|
||||
|
||||
# stack the new columns and return to the original shape
|
||||
geodetic = np.column_stack((lat, lon, h))
|
||||
return geodetic.reshape(input_shape)
|
||||
|
||||
|
||||
|
||||
class LocalCoord(object):
|
||||
"""
|
||||
Allows conversions to local frames. In this case NED.
|
||||
|
|
|
@ -182,4 +182,4 @@ BO_TX_BU_ 769 : NEO,ADAS;
|
|||
|
||||
|
||||
CM_ SG_ 1024 RADAR_STATE "need to find out more diagnostic values";
|
||||
VAL_ 1024 RADAR_STATE 121 "ok" 110 "faulted";
|
||||
VAL_ 1024 RADAR_STATE 121 "ok" 110 "faulted" 105 "wrong_config";
|
||||
|
|
|
@ -37,12 +37,15 @@ BU_: XXX
|
|||
|
||||
|
||||
BO_ 258 STEERING: 8 XXX
|
||||
SG_ INCREMENTING_STEERING : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM_STEERING : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ UNKNOWN_STEERING : 48|3@1+ (1,0) [0|15] "" XXX
|
||||
SG_ STEERING_RATE : 20|13@0+ (0.3187251,-1305.498) [0|8191] "deg/s" XXX
|
||||
SG_ STEER_ANGLE : 4|13@0+ (0.3187251,-1307.888) [-360|360] "deg" XXX
|
||||
SG_ STEERING_RATE : 20|13@0+ (1,-4096) [0|8191] "" XXX
|
||||
|
||||
BO_ 514 SPEED: 4 XXX
|
||||
SG_ SPEED_LEFT : 7|16@0+ (0.07,0) [0|65535] "m/s" XXX
|
||||
SG_ SPEED_RIGHT : 23|16@0+ (0.07,0) [0|1023] "m/s" XXX
|
||||
BO_ 514 SPEED_1: 4 XXX
|
||||
SG_ SPEED_LEFT : 7|12@0+ (0.071028,0) [0|65535] "m/s" XXX
|
||||
SG_ SPEED_RIGHT : 23|12@0+ (0.071028,0) [0|1023] "m/s" XXX
|
||||
|
||||
BO_ 653 BRAKE_MODULE: 2 XXX
|
||||
SG_ BRAKE_PRESSURE : 15|8@0+ (1,0) [0|255] "" XXX
|
||||
|
@ -59,49 +62,365 @@ BO_ 820 DOORS: 8 XXX
|
|||
SG_ HIGH_BEAM_DISPLAY : 58|1@1+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 746 GEAR: 5 XXX
|
||||
SG_ PRNDL : 0|3@1+ (1,0) [0|7] "" XXX
|
||||
SG_ PRNDL : 2|3@0+ (1,0) [0|7] "" XXX
|
||||
SG_ GEAR_CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ GEAR_INCREMENTING : 31|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 284 NEW_MSG_1: 8 XXX
|
||||
SG_ BRAKE_RELATED : 3|12@0+ (1,0) [0|255] "" XXX
|
||||
SG_ BRAKE_RELATED_2 : 17|10@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SPEED : 37|14@0+ (1,0) [0|255] "" XXX
|
||||
BO_ 284 BRAKE_1: 8 XXX
|
||||
SG_ SPEED_RELATED_1 : 37|14@0+ (1,0) [0|255] "" XXX
|
||||
SG_ BRAKE_RELATED_1_2 : 18|11@0+ (1,0) [0|255] "" XXX
|
||||
SG_ BRAKE_RELATED_1_1 : 3|12@0+ (1,0) [0|255] "" XXX
|
||||
SG_ INCREMENTING_BRAKE : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM_BRAKE : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 320 NEW_MSG_2: 8 XXX
|
||||
SG_ SPEED_RELATED : 47|8@0+ (1,0) [0|63] "" XXX
|
||||
SG_ BRAKE_PRESSED : 2|3@0+ (1,0) [0|7] "" XXX
|
||||
BO_ 320 BRAKE_2: 8 XXX
|
||||
SG_ SPEED_RELATED_2 : 47|8@0+ (1,0) [0|63] "" XXX
|
||||
SG_ INCREMENTING_140 : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM_140 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ BRAKE_PRESSED_2 : 2|3@0+ (1,0) [0|7] "" XXX
|
||||
SG_ BRAKE_PRESSED_ACC : 6|1@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 736 TRIP: 8 XXX
|
||||
SG_ DISTANCE_COUNTER : 7|16@0+ (0,0) [0|65535] "Meters" XXX
|
||||
SG_ DISTANCE_COUNTER : 7|16@0+ (1,0) [0|65535] "Meters" XXX
|
||||
SG_ DISTANCE_COUNTER_2 : 23|16@0+ (1,0) [0|65535] "Meters" XXX
|
||||
|
||||
BO_ 344 WHEEL_SPEEDS: 8 XXX
|
||||
SG_ WHEEL_SPEED_FL : 1|10@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ WHEEL_SPEED_FR : 17|10@0+ (1,0) [0|255] "" XXX
|
||||
SG_ WHEEL_SPEED_RL : 33|10@0+ (1,0) [0|3] "" XXX
|
||||
SG_ WHEEL_SPEED_RR : 49|10@0+ (1,0) [0|255] "" XXX
|
||||
SG_ WHEEL_SPEED_FL : 3|12@0+ (0.0189408,0) [0|65535] "m/s" XXX
|
||||
SG_ WHEEL_SPEED_RR : 51|12@0+ (0.0189408,0) [0|255] "m/s" XXX
|
||||
SG_ WHEEL_SPEED_RL : 35|12@0+ (0.0189408,0) [0|3] "m/s" XXX
|
||||
SG_ WHEEL_SPEED_FR : 19|12@0+ (0.0189408,0) [0|255] "m/s" XXX
|
||||
|
||||
BO_ 792 STEERING_LEVERS: 8 XXX
|
||||
SG_ HIGH_BEAM_PUSHED_IN : 2|1@0+ (1,0) [0|3] "" XXX
|
||||
SG_ TURN_SIGNALS : 1|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ HIGH_BEAM_PUSHED_IN : 2|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ HIGH_BEAM_FLASH : 3|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ HIGH_BEAM_FLASH : 3|1@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 264 ACCEL_PEDAL_MSG: 8 XXX
|
||||
SG_ ACCEL_PEDAL : 32|4@1+ (1,-7) [0|15] "" XXX
|
||||
SG_ INCREMENTING_ACCEL_PEDAL : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM_ACCEL_PEDAL : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ACCEL_PEDAL : 35|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 464 SEATBELT_STATUS: 8 XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 13|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 544 LKAS_INDICATOR_1: 8 XXX
|
||||
SG_ LKAS_IS_GREEN : 23|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ AUTO_PARK_HAS_CONTROL_1 : 20|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ AUTO_PARK_HAS_CONTROL_2 : 51|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ INCREMENTING_220 : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM_220 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ UNKNOWN_220_2 : 34|11@0+ (1,0) [0|255] "" XXX
|
||||
SG_ UNKNOWN_220_1 : 19|12@0+ (1,0) [0|4095] "" XXX
|
||||
SG_ UNKNOWN_220_0 : 2|11@0+ (1,0) [0|63] "" XXX
|
||||
|
||||
BO_ 658 LKAS_INDICATOR_2: 6 XXX
|
||||
SG_ LKAS_INCREMENTING : 39|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ LKAS_CHECKSUM_2 : 40|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ LKAS_STEERING_TORQUE_MAYBE : 3|12@0- (1,0) [0|63] "" XXX
|
||||
|
||||
BO_ 678 LKAS_INDICATOR_3: 8 XXX
|
||||
SG_ WARNING_PLACE_HANDS : 22|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ LKAS_WHITE_OR_YELLOW : 0|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ LKAS_IS_YELLOW_2 : 19|1@1+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 705 AUTO_PARK_BUTTON: 8 XXX
|
||||
SG_ AUTO_PARK_TOGGLE_2 : 8|1@1+ (1,0) [0|1] "" XXX
|
||||
SG_ AUTO_PARK_TOGGLE_1 : 11|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ INCREASING_UNKNOWN : 32|7@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 719 AUTO_PARK_SIGNALS_1: 8 XXX
|
||||
SG_ AUTO_PARK_UNKNOWN_1 : 7|16@0+ (1,0) [0|31] "" XXX
|
||||
|
||||
BO_ 671 AUTO_PARK_SIGNALS_2: 8 XXX
|
||||
SG_ AUTO_PARK_PARALLEL : 21|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ AUTO_PARK_PERPENDICULAR_1 : 22|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ INCREMENTING : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ AUTO_PARK_CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ AUTO_PARK_MAYBE_TURNING : 3|12@0+ (1,0) [0|1023] "" XXX
|
||||
SG_ AUTO_PARK_TURNING_STATUS : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 784 AUTO_PARK_LESS_INTERESTING: 8 XXX
|
||||
SG_ INCREASING_UNKNOWN : 48|8@1+ (1,0) [0|7] "" XXX
|
||||
SG_ AUTO_PARK_PERPENDICULAR_2 : 61|1@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 826 AUTO_PARK_SIGNALS_3: 8 XXX
|
||||
SG_ AUTO_PARK_HAS_CONTROL_3 : 1|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ HUMAN_HAS_CONTROL : 2|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ AUTO_PARK_GEAR_1 : 27|4@0+ (1,0) [0|255] "" XXX
|
||||
SG_ AUTO_PARK_GEAR_2 : 32|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ AUTO_PARK_GEAR_3 : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 332 STEERING_2: 8 XXX
|
||||
SG_ INCREMENTING_14C : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ENERGY_RELATED : 39|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ STEER_ANGLE_2 : 7|13@0+ (0.3187251,-1307.888) [-360|360] "deg" XXX
|
||||
|
||||
BO_ 720 BLIND_SPOT_WARNINGS: 6 XXX
|
||||
SG_ BLIND_SPOT_RIGHT : 5|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BLIND_SPOT_LEFT : 2|1@1+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 331 BRAKE_3: 8 XXX
|
||||
SG_ BRAKE_RELATED_3 : 7|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ INCREMENTING_14B : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM_14B : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 608 PARKSENSE_SIGNAL: 8 XXX
|
||||
SG_ PARKSENSE_DISABLED : 34|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ INCREMENTING_260 : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM_260 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ IN_REVERSE : 10|1@1+ (1,0) [0|255] "" XXX
|
||||
SG_ AUTO_PARK_HAS_CONTROL_1 : 16|1@1+ (1,0) [0|255] "" XXX
|
||||
SG_ HUMAN_HAS_CONTROL : 17|1@1+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 729 LKAS_STATUS_1: 5 XXX
|
||||
SG_ LKAS_STATUS_OK : 31|16@0+ (1,0) [0|65535] "" XXX
|
||||
|
||||
BO_ 274 NEW_MSG_112: 2 XXX
|
||||
|
||||
BO_ 290 NEW_MSG_122: 6 XXX
|
||||
|
||||
BO_ 376 NEW_MSG_178: 3 XXX
|
||||
|
||||
BO_ 288 ACCEL_RELATED_120: 7 XXX
|
||||
SG_ UNKNOWN_INCREMENTING_120 : 47|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ UNKNOWN_CHECKSUM_120 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ACCEL : 16|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ GAS_ENGINE_RPM_MAYBE : 31|16@0+ (1,0) [0|65535] "" XXX
|
||||
|
||||
BO_ 257 ACCEL_RELATED_101: 5 XXX
|
||||
SG_ ENERGY_OR_RPM : 24|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 388 NEW_MSG_184: 4 XXX
|
||||
|
||||
BO_ 448 NEW_MSG_1c0: 6 XXX
|
||||
|
||||
BO_ 456 NEW_MSG_1c8: 4 XXX
|
||||
|
||||
BO_ 560 NEW_MSG_230: 4 XXX
|
||||
|
||||
BO_ 564 NEW_MSG_234: 4 XXX
|
||||
|
||||
BO_ 571 WHEEL_BUTTONS: 3 XXX
|
||||
SG_ CHECKSUM_23B : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ACC_FOLLOW_DEC : 1|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ ACC_SPEED_INC : 2|1@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ACC_SPEED_DEC : 3|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ ACC_FOLLOW_INC : 8|1@1+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 15|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 669 NEW_MSG_29d: 3 XXX
|
||||
SG_ INCREMENTING_29D : 15|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM_29D : 16|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 825 NEW_MSG_339: 2 XXX
|
||||
|
||||
BO_ 856 NEW_MSG_358: 4 XXX
|
||||
|
||||
BO_ 860 NEW_MSG_35c: 6 XXX
|
||||
|
||||
BO_ 924 NEW_MSG_39c: 3 XXX
|
||||
|
||||
BO_ 969 NEW_MSG_3c9: 4 XXX
|
||||
|
||||
BO_ 974 NEW_MSG_3ce: 5 XXX
|
||||
|
||||
BO_ 993 NEW_MSG_3e1: 7 XXX
|
||||
|
||||
BO_ 838 NEW_MSG_346: 2 XXX
|
||||
|
||||
BO_ 926 NEW_MSG_39e: 3 XXX
|
||||
|
||||
BO_ 168 ACCEL_RELATED_a8: 8 XXX
|
||||
SG_ ACCEL_RELATED : 23|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ INCREMENTING_A8 : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM_A8 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 270 ACCEL_RELATED_10e: 8 XXX
|
||||
SG_ ACCEL_OR_RPM : 7|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ INCREMENTING_ACCEL : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM_ACCEL : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ELECTRIC_MOTOR : 23|16@0+ (1,0) [0|65535] "" XXX
|
||||
|
||||
BO_ 291 ENERGY_RELATED_123: 8 XXX
|
||||
SG_ ENERGY_GAIN_LOSS : 18|11@0- (1,0) [0|255] "" XXX
|
||||
SG_ INCREMENTING_123 : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM_123 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ENERGY_SMOOTHER_CURVE : 35|12@0+ (1,0) [0|2047] "" XXX
|
||||
|
||||
BO_ 294 ENERGY_RELATED_126: 8 XXX
|
||||
SG_ CHECKSUM_126 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ UNKNOWN_126_1 : 3|12@0+ (1,0) [0|4095] "" XXX
|
||||
SG_ INCREMENTING_126 : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ UNKNOWN_126_2 : 35|12@0+ (1,0) [0|4095] "" XXX
|
||||
SG_ ENERGY_GAIN_LOSS_NOISY : 19|12@0+ (1,0) [0|2047] "" XXX
|
||||
|
||||
BO_ 300 NEW_MSG_12C: 8 XXX
|
||||
|
||||
BO_ 308 ACCEL_GAS_134: 8 XXX
|
||||
SG_ INCREMENTING_134 : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ACCEL_134 : 40|4@1+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 532 ENERGY_RELATED_214: 8 XXX
|
||||
SG_ NOISY_SLOWLY_DECREASING : 16|9@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ENERGY_RELATED : 0|9@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 559 ACCEL_GAS_22F: 8 XXX
|
||||
SG_ ACCEL_22F : 0|4@1+ (1,0) [0|255] "" XXX
|
||||
SG_ INCREMENTING_22F : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM_22F : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 655 CHARGING_MAYBE_28F: 8 XXX
|
||||
SG_ CHARGING : 0|2@1+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 660 BRAKE_RELATED_294: 8 XXX
|
||||
SG_ INCREMENTING_294 : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM_294 : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ BRAKE_PERHAPS_294 : 24|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 764 ACCEL_RELATED_2FC: 8 XXX
|
||||
SG_ ACCEL_2FC : 8|6@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 816 TRACTION_BUTTON: 8 XXX
|
||||
SG_ TRACTION_OFF : 19|1@1+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 878 ACCEL_RELATED_36E: 8 XXX
|
||||
SG_ ACCEL_OR_RPM_2 : 15|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ACCEL_OR_RPM_1 : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 324 SPEED_2: 8 XXX
|
||||
SG_ SPEED_2 : 31|16@0+ (0.01,0) [0|255] "m/s" XXX
|
||||
|
||||
BO_ 501 DASHBOARD: 8 XXX
|
||||
SG_ ACC_SPEED_CONFIG_KPH : 15|8@0+ (1,0) [0|3] "km/h" XXX
|
||||
SG_ ACC_SPEED_CONFIG_MPH : 23|8@0+ (1,0) [0|3] "mph" XXX
|
||||
SG_ ACC_DISTANCE_CONFIG_1 : 1|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ ACC_DISTANCE_CONFIG_2 : 41|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SPEED_DIGITAL : 63|8@0+ (1,0) [0|255] "mph" XXX
|
||||
|
||||
BO_ 639 NEW_MSG_27f: 8 XXX
|
||||
SG_ INCREASING : 40|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 701 NEW_MSG_2bd: 8 XXX
|
||||
SG_ unknown_1 : 32|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 832 UNKNOWN_340: 8 XXX
|
||||
SG_ SPEED_DIGITAL : 56|8@1+ (1,0) [0|255] "mph" XXX
|
||||
|
||||
BO_ 848 UNKNOWN_350: 8 XXX
|
||||
SG_ INCREASING_LSB : 0|6@1+ (1,0) [0|255] "" XXX
|
||||
SG_ INCREASING_MSB : 12|5@0+ (1,0) [0|31] "" XXX
|
||||
|
||||
BO_ 908 NEW_MSG_38c: 8 XXX
|
||||
SG_ INCREASING_MSB : 44|5@0+ (1,0) [0|31] "" XXX
|
||||
SG_ INCREASING_LSB : 56|6@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 938 NEW_MSG_3aa: 8 XXX
|
||||
SG_ INCREASING_UNKNOWN_1 : 32|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ INCREASING_UNKNOWN_2 : 56|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 940 NEW_MSG_3ac: 8 XXX
|
||||
SG_ INCREASING_1 : 32|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ INCREASING_2 : 56|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 941 NEW_MSG_3ad: 8 XXX
|
||||
SG_ INCREASING_1 : 32|5@1+ (1,0) [0|31] "" XXX
|
||||
SG_ INCREASING_2 : 56|8@1+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 500 ACC_2: 8 XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ACC_STATUS_1 : 7|3@0+ (1,0) [0|255] "" XXX
|
||||
SG_ BRAKE_MAYBE : 18|11@0+ (1,0) [0|255] "" XXX
|
||||
SG_ ACC_STATUS_2 : 21|3@0+ (1,0) [0|255] "" XXX
|
||||
SG_ BRAKE_BOOL_1 : 36|1@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 625 ACC_1: 8 XXX
|
||||
SG_ SPEED : 24|8@1+ (1,0) [0|255] "km/h" XXX
|
||||
SG_ ACCEL_PERHAPS : 39|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 268 ACC_10c: 8 XXX
|
||||
SG_ BRAKE_PERHAPS : 48|1@1+ (1,0) [0|3] "" XXX
|
||||
SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 384 NEW_MSG_180: 8 XXX
|
||||
SG_ NEW_SIGNAL_2 : 15|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_1 : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ NEW_SIGNAL_3 : 32|8@1+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 853 NEW_MSG_355: 8 XXX
|
||||
|
||||
BO_ 939 NEW_MSG_3ab: 8 XXX
|
||||
|
||||
BO_ 512 NEW_MSG_200: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 16|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ INCREASING : 27|12@0+ (1,0) [0|127] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
|
||||
|
||||
|
||||
CM_ SG_ 258 UNKNOWN_STEERING "never goes above 4. see if human-applied torque";
|
||||
CM_ SG_ 258 STEER_ANGLE "positive is left (counter-clockwise)";
|
||||
CM_ SG_ 514 SPEED_LEFT "TODO find upper limit";
|
||||
CM_ SG_ 653 BRAKE_PRESSURE "max seems to be 148";
|
||||
CM_ SG_ 820 TURN_LIGHT_LEFT "oscillates with the light blinking";
|
||||
CM_ SG_ 820 TURN_LIGHT_RIGHT "hazard blinks both right and left lights";
|
||||
CM_ SG_ 746 PRNDL "4=D, 3=N, 2=R, 1=P";
|
||||
CM_ SG_ 284 BRAKE_RELATED "Correlates with braking";
|
||||
CM_ SG_ 284 SPEED "Another Speed Signal, Maybe RPMs?";
|
||||
CM_ SG_ 320 BRAKE_PRESSED "Value is 5 when brake is pressed";
|
||||
CM_ SG_ 746 GEAR_CHECKSUM "different than the LKAS checksum. unknown non-simple algorithm. just build a lookup table for it.";
|
||||
CM_ SG_ 284 SPEED_RELATED_1 "Another Speed Signal, Maybe RPMs?";
|
||||
CM_ SG_ 284 BRAKE_RELATED_1_1 "Correlates with braking";
|
||||
CM_ SG_ 320 BRAKE_PRESSED_2 "Value is 5 when brake is pressed by human, 1 when ACC brake";
|
||||
CM_ SG_ 320 BRAKE_PRESSED_ACC "set when ACC brakes";
|
||||
CM_ SG_ 792 TURN_SIGNALS "1=Left, 2=Right";
|
||||
CM_ SG_ 792 HIGH_BEAM_FLASH "use this for genericToggle";
|
||||
CM_ SG_ 264 ACCEL_PEDAL "not in ACC so seems to be actual pedal. Use for gasPressed";
|
||||
CM_ SG_ 544 AUTO_PARK_HAS_CONTROL_1 "set when autopark has control";
|
||||
CM_ SG_ 658 LKAS_INCREMENTING "each message increments, 0..f";
|
||||
CM_ SG_ 658 LKAS_CHECKSUM_2 "checksum calculated with https://gist.github.com/adhintz/94bf8d19b9075539f50172ab0fb24ba1";
|
||||
CM_ SG_ 658 LKAS_STEERING_TORQUE_MAYBE "1024 is straight. most sent by stock system is 1024+-230. + is left. typically changes by 2 or 3 each 0.01s";
|
||||
CM_ SG_ 678 WARNING_PLACE_HANDS "set when warning displays place hands on steering wheel";
|
||||
CM_ SG_ 678 LKAS_WHITE_OR_YELLOW "set when indicator is yellow or white. could indicate lkas not on track.";
|
||||
CM_ SG_ 678 LKAS_IS_YELLOW_2 "set when indicator is yellow. could indicate lkas is steering.";
|
||||
CM_ SG_ 705 AUTO_PARK_TOGGLE_1 "set briefly when turning on or off self-parking";
|
||||
CM_ SG_ 705 INCREASING_UNKNOWN "sometimes decreasing";
|
||||
CM_ SG_ 671 AUTO_PARK_PARALLEL "parallel parking mode";
|
||||
CM_ SG_ 671 AUTO_PARK_PERPENDICULAR_1 "perpendicular parking mode";
|
||||
CM_ SG_ 671 AUTO_PARK_MAYBE_TURNING "something with autopark turning the steering wheel maybe.";
|
||||
CM_ SG_ 671 AUTO_PARK_TURNING_STATUS "0 when not steering. when steering starts, 4 for two packets, and then 5 for the rest";
|
||||
CM_ SG_ 784 INCREASING_UNKNOWN "perhaps distance traveled";
|
||||
CM_ SG_ 826 AUTO_PARK_GEAR_1 "Reverse=0, Forward=f";
|
||||
CM_ SG_ 826 AUTO_PARK_GEAR_2 "Reverse=0, Forward=f";
|
||||
CM_ SG_ 826 AUTO_PARK_GEAR_3 "Reverse=0, Forward=f";
|
||||
CM_ SG_ 332 STEER_ANGLE_2 "slightly lags the other steer_angle signal. also more noisy.";
|
||||
CM_ SG_ 720 BLIND_SPOT_RIGHT "yellow triangle alert on side view mirror when a car is in your blind spot";
|
||||
CM_ SG_ 608 PARKSENSE_DISABLED "set if parksense is disabled";
|
||||
CM_ SG_ 729 LKAS_STATUS_OK "Set to 0x0820 when LKAS system is plugged in.";
|
||||
CM_ SG_ 288 UNKNOWN_CHECKSUM_120 "not the LKAS checksum";
|
||||
CM_ SG_ 288 GAS_ENGINE_RPM_MAYBE "lags acceleration, perhaps gas engine";
|
||||
CM_ SG_ 257 ENERGY_OR_RPM "perhaps energy consumption or RPMs";
|
||||
CM_ SG_ 270 ELECTRIC_MOTOR "0x7fff indicates electric motor not in use";
|
||||
CM_ SG_ 291 ENERGY_GAIN_LOSS "unsure what this actually is";
|
||||
CM_ SG_ 291 ENERGY_SMOOTHER_CURVE "unusre what it is, but smoother";
|
||||
CM_ SG_ 532 NOISY_SLOWLY_DECREASING "perhaps battery but do not know";
|
||||
CM_ SG_ 816 TRACTION_OFF "set when traction off button is enabled";
|
||||
CM_ SG_ 324 SPEED_2 "signal is approx half other speeds";
|
||||
CM_ SG_ 501 ACC_SPEED_CONFIG_KPH "speed configured for ACC";
|
||||
CM_ SG_ 501 ACC_SPEED_CONFIG_MPH "speed configured for ACC";
|
||||
CM_ SG_ 639 INCREASING "perhaps number of seconds divided by two for this drive";
|
||||
CM_ SG_ 848 INCREASING_LSB "lower part of time counter";
|
||||
CM_ SG_ 848 INCREASING_MSB "upper part of time counter";
|
||||
CM_ SG_ 908 INCREASING_MSB "time based";
|
||||
CM_ SG_ 500 ACC_STATUS_1 "2 briefly (9 packets) when ACC goes to green, 1 help when ACC coming to a stop and at a stop";
|
||||
CM_ SG_ 500 BRAKE_MAYBE "2046 in non-ACC and non-decel. Signal on deceleration. 818 for already stopped break.";
|
||||
CM_ SG_ 500 ACC_STATUS_2 "set to 1 in non-ACC, 3 when ACC enabled (white icon), and 7 when ACC in use (green icon)";
|
||||
CM_ SG_ 500 BRAKE_BOOL_1 "set to 1 when ACC decel. 0 on non-ACC and accel.";
|
||||
CM_ SG_ 625 SPEED "zero on non-acc drives";
|
||||
CM_ SG_ 625 ACCEL_PERHAPS "set to 7767 on non-ACC drives. ACC drive 40k is constant speed, 42k is accelerating";
|
||||
CM_ SG_ 268 BRAKE_PERHAPS "triggers only on ACC braking";
|
||||
CM_ SG_ 384 NEW_SIGNAL_1 "set in ACC gas driving. not set in electric human. not sure about gas human driving.";
|
||||
VAL_ 746 PRNDL 4 "Drive" 3 "Neutral" 2 "Reverse" 1 "Park" ;
|
||||
VAL_ 792 TURN_SIGNALS 2 "Right" 1 "Left" ;
|
||||
|
|
|
@ -0,0 +1,230 @@
|
|||
VERSION ""
|
||||
|
||||
|
||||
NS_ :
|
||||
NS_DESC_
|
||||
CM_
|
||||
BA_DEF_
|
||||
BA_
|
||||
VAL_
|
||||
CAT_DEF_
|
||||
CAT_
|
||||
FILTER
|
||||
BA_DEF_DEF_
|
||||
EV_DATA_
|
||||
ENVVAR_DATA_
|
||||
SGTYPE_
|
||||
SGTYPE_VAL_
|
||||
BA_DEF_SGTYPE_
|
||||
BA_SGTYPE_
|
||||
SIG_TYPE_REF_
|
||||
VAL_TABLE_
|
||||
SIG_GROUP_
|
||||
SIG_VALTYPE_
|
||||
SIGTYPE_VALTYPE_
|
||||
BO_TX_BU_
|
||||
BA_DEF_REL_
|
||||
BA_REL_
|
||||
BA_DEF_DEF_REL_
|
||||
BU_SG_REL_
|
||||
BU_EV_REL_
|
||||
BU_BO_REL_
|
||||
SG_MUL_VAL_
|
||||
|
||||
BS_:
|
||||
|
||||
BU_: XXX
|
||||
|
||||
|
||||
BO_ 544 a_1: 8 XXX
|
||||
SG_ track_id : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ REL_ACCEL : 3|12@0+ (1,0) [0|31] "" XXX
|
||||
SG_ status1 : 23|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ REL_SPEED : 19|12@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX
|
||||
SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 576 b_1: 8 XXX
|
||||
SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 608 a_2: 8 XXX
|
||||
SG_ track_id : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ REL_ACCEL : 3|12@0+ (1,0) [0|31] "" XXX
|
||||
SG_ status1 : 23|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ REL_SPEED : 19|12@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX
|
||||
SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 640 b_2: 8 XXX
|
||||
SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 644 a_3: 8 XXX
|
||||
SG_ track_id : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ REL_ACCEL : 3|12@0+ (1,0) [0|31] "" XXX
|
||||
SG_ status1 : 23|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ REL_SPEED : 19|12@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX
|
||||
SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 648 b_3: 8 XXX
|
||||
SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 652 a_4: 8 XXX
|
||||
SG_ track_id : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ REL_ACCEL : 3|12@0+ (1,0) [0|31] "" XXX
|
||||
SG_ status1 : 23|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ REL_SPEED : 19|12@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ status2 : 39|6@0+ (1,0) [0|15] "" XXX
|
||||
SG_ sig2 : 33|10@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 656 b_4: 8 XXX
|
||||
SG_ sig0 : 0|8@1+ (1,0) [0|255] "" XXX
|
||||
SG_ sig1 : 15|16@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ sig2 : 31|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros : 47|12@0+ (1,0) [0|255] "" XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 512 unknown_200: 8 XXX
|
||||
SG_ COUNTER : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ increasing : 31|16@0+ (1,0) [0|255] "" XXX
|
||||
SG_ zeros_0 : 3|12@0+ (1,0) [0|63] "" XXX
|
||||
SG_ zeros_1 : 47|12@0+ (1,0) [0|63] "" XXX
|
||||
SG_ status0 : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ unknown_0 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 514 unknown_202: 8 XXX
|
||||
SG_ COUNTER : 43|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ sig3 : 31|8@0+ (1,0) [0|65535] "" XXX
|
||||
SG_ increasing : 39|12@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 706 c_1: 8 XXX
|
||||
SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX
|
||||
SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX
|
||||
|
||||
BO_ 708 c_2: 8 XXX
|
||||
SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX
|
||||
SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX
|
||||
SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 710 c_3: 8 XXX
|
||||
SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX
|
||||
SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX
|
||||
SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 712 c_4: 8 XXX
|
||||
SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX
|
||||
SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX
|
||||
SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 714 c_5: 8 XXX
|
||||
SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX
|
||||
SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX
|
||||
SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 716 c_6: 8 XXX
|
||||
SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX
|
||||
SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX
|
||||
SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 718 c_7: 8 XXX
|
||||
SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX
|
||||
SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX
|
||||
SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 720 c_8: 8 XXX
|
||||
SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX
|
||||
SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX
|
||||
SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 722 c_9: 8 XXX
|
||||
SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX
|
||||
SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX
|
||||
SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 724 c_10: 8 XXX
|
||||
SG_ LAT_DIST : 18|11@0+ (0.005,-1000) [0|2047] "m" XXX
|
||||
SG_ LONG_DIST : 34|11@0+ (0.073,0) [0|255] "m" XXX
|
||||
SG_ COUNTER : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 674 d_1: 8 XXX
|
||||
SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX
|
||||
|
||||
BO_ 676 d_2: 8 XXX
|
||||
SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX
|
||||
|
||||
BO_ 678 d_3: 8 XXX
|
||||
SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX
|
||||
|
||||
BO_ 680 d_4: 8 XXX
|
||||
SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX
|
||||
|
||||
BO_ 682 d_5: 8 XXX
|
||||
SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX
|
||||
|
||||
BO_ 684 d_6: 8 XXX
|
||||
SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX
|
||||
|
||||
BO_ 686 d_7: 8 XXX
|
||||
SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX
|
||||
|
||||
BO_ 688 d_8: 8 XXX
|
||||
SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX
|
||||
|
||||
BO_ 690 d_9: 8 XXX
|
||||
SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX
|
||||
|
||||
BO_ 692 d_10: 8 XXX
|
||||
SG_ REL_SPEED : 17|10@0+ (0.2857,-146.278) [0|1023] "m/s" XXX
|
||||
|
||||
BO_ 672 NEW_MSG_5: 8 XXX
|
||||
SG_ NEW_SIGNAL_1 : 9|10@0+ (1,0) [0|1023] "" XXX
|
||||
SG_ NEW_SIGNAL_2 : 45|10@0+ (1,0) [0|1023] "" XXX
|
||||
|
||||
|
||||
|
||||
|
||||
CM_ SG_ 544 track_id "for message a_1 track_id is always 1, similar for other messages and track_id";
|
||||
CM_ SG_ 544 REL_ACCEL "perhaps REL_ACCEL because it responds faster and before REL_SPEED";
|
||||
CM_ SG_ 544 sig2 "perhaps distance to object. LONG_DIST or REL_ACCEL or REL_SPEED";
|
||||
CM_ SG_ 576 zeros "not always zero, sometimes has value when another car changes lanes";
|
||||
CM_ SG_ 706 LAT_DIST "positive is to the right, negative is to the left";
|
|
@ -0,0 +1,97 @@
|
|||
CM_ "IMPORT _honda_2017.dbc"
|
||||
CM_ "IMPORT _comma.dbc"
|
||||
|
||||
BO_ 145 KINEMATICS: 8 XXX
|
||||
SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON
|
||||
|
||||
BO_ 228 STEERING_CONTROL: 5 ADAS
|
||||
SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS
|
||||
SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS
|
||||
SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS
|
||||
SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS
|
||||
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS
|
||||
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS
|
||||
|
||||
BO_ 304 GAS_PEDAL_2: 8 PCM
|
||||
SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON
|
||||
SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON
|
||||
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 342 STEERING_SENSORS: 6 EPS
|
||||
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON
|
||||
SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 399 STEER_STATUS: 7 EPS
|
||||
SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON
|
||||
SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON
|
||||
SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 401 GEARBOX: 8 PCM
|
||||
SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON
|
||||
SG_ GEAR : 43|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 420 VSA_STATUS: 8 VSA
|
||||
SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON
|
||||
SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 422 SCM_BUTTONS: 8 SCM
|
||||
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON
|
||||
SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 487 BRAKE_PRESSURE: 4 VSA
|
||||
SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON
|
||||
SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON
|
||||
SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 660 SCM_FEEDBACK: 8 SCM
|
||||
SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 862 HIGHBEAM_CONTROL: 8 ADAS
|
||||
SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY
|
||||
SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 884 STALK_STATUS: 8 XXX
|
||||
SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
|
||||
CM_ SG_ 401 GEAR "10 = reverse, 11 = transition";
|
||||
CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged";
|
||||
|
||||
VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ;
|
||||
VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ;
|
||||
VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ;
|
||||
VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ;
|
||||
VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ;
|
||||
VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ;
|
||||
|
||||
CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";
|
|
@ -0,0 +1,36 @@
|
|||
CM_ "IMPORT _toyota_2017.dbc"
|
||||
CM_ "IMPORT _comma.dbc"
|
||||
|
||||
BO_ 295 GEAR_PACKET: 8 XXX
|
||||
SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX
|
||||
SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 550 BRAKE_MODULE: 8 XXX
|
||||
SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX
|
||||
SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX
|
||||
SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 581 GAS_PEDAL: 8 XXX
|
||||
SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX
|
||||
|
||||
BO_ 608 STEER_TORQUE_SENSOR: 8 XXX
|
||||
SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX
|
||||
SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX
|
||||
SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 610 EPS_STATUS: 8 EPS
|
||||
SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX
|
||||
SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force";
|
||||
CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8";
|
||||
CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others";
|
||||
CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered";
|
||||
VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B";
|
||||
VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
|
||||
VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby";
|
|
@ -0,0 +1,326 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here"
|
||||
BO_ 512 GAS_COMMAND: 6 EON
|
||||
SG_ GAS_COMMAND : 7|16@0+ (0.253984064,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ GAS_COMMAND2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" INTERCEPTOR
|
||||
SG_ ENABLE : 39|1@0+ (1,0) [0|1] "" INTERCEPTOR
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" INTERCEPTOR
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" INTERCEPTOR
|
||||
|
||||
BO_ 513 GAS_SENSOR: 6 INTERCEPTOR
|
||||
SG_ INTERCEPTOR_GAS : 7|16@0+ (0.253984064,-83.3) [0|1] "" EON
|
||||
SG_ INTERCEPTOR_GAS2 : 23|16@0+ (0.126992032,-83.3) [0|1] "" EON
|
||||
SG_ STATE : 39|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
VAL_ 513 STATE 5 "FAULT_TIMEOUT" 4 "FAULT_STARTUP" 3 "FAULT_SCE" 2 "FAULT_SEND" 1 "FAULT_BAD_CHECKSUM" 0 "NO_FAULT" ;
|
||||
|
||||
|
||||
CM_ "Imported file _honda_2017.dbc starts here"
|
||||
VERSION ""
|
||||
|
||||
|
||||
NS_ :
|
||||
NS_DESC_
|
||||
CM_
|
||||
BA_DEF_
|
||||
BA_
|
||||
VAL_
|
||||
CAT_DEF_
|
||||
CAT_
|
||||
FILTER
|
||||
BA_DEF_DEF_
|
||||
EV_DATA_
|
||||
ENVVAR_DATA_
|
||||
SGTYPE_
|
||||
SGTYPE_VAL_
|
||||
BA_DEF_SGTYPE_
|
||||
BA_SGTYPE_
|
||||
SIG_TYPE_REF_
|
||||
VAL_TABLE_
|
||||
SIG_GROUP_
|
||||
SIG_VALTYPE_
|
||||
SIGTYPE_VALTYPE_
|
||||
BO_TX_BU_
|
||||
BA_DEF_REL_
|
||||
BA_REL_
|
||||
BA_DEF_DEF_REL_
|
||||
BU_SG_REL_
|
||||
BU_EV_REL_
|
||||
BU_BO_REL_
|
||||
SG_MUL_VAL_
|
||||
|
||||
BU_: EBCM ADAS PCM EPS VSA SCM BDY XXX EPB EON
|
||||
|
||||
BO_ 344 ENGINE_DATA: 8 PCM
|
||||
SG_ XMISSION_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON
|
||||
SG_ XMISSION_SPEED2 : 39|16@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ ODOMETER : 55|8@0+ (0.010588,0) [0|255] "km" XXX
|
||||
|
||||
BO_ 380 POWERTRAIN_DATA: 8 PCM
|
||||
SG_ PEDAL_GAS : 7|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ ENGINE_RPM : 23|16@0+ (1,0) [0|15000] "rpm" EON
|
||||
SG_ GAS_PRESSED : 39|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ ACC_STATUS : 38|1@0+ (1,0) [0|1] "rpm" EON
|
||||
SG_ BOH_17C : 37|5@0+ (1,0) [0|1] "rpm" EON
|
||||
SG_ BRAKE_SWITCH : 32|1@0+ (1,0) [0|1] "rpm" EON
|
||||
SG_ BOH2_17C : 47|10@0+ (1,0) [0|1] "rpm" EON
|
||||
SG_ BRAKE_PRESSED : 53|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BOH3_17C : 52|5@0+ (1,0) [0|1] "rpm" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 432 STANDSTILL: 7 VSA
|
||||
SG_ CONTROLLED_STANDSTILL : 0|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ WHEELS_MOVING : 12|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_ERROR_1 : 11|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_ERROR_2 : 9|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 464 WHEEL_SPEEDS: 8 VSA
|
||||
SG_ WHEEL_SPEED_FL : 7|15@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ WHEEL_SPEED_FR : 8|15@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ WHEEL_SPEED_RL : 25|15@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ WHEEL_SPEED_RR : 42|15@0+ (0.01,0) [0|250] "kph" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 490 VEHICLE_DYNAMICS: 8 VSA
|
||||
SG_ LONG_ACCEL : 23|16@0- (0.0015384,0) [-20|20] "m/s2" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 506 BRAKE_COMMAND: 8 ADAS
|
||||
SG_ COMPUTER_BRAKE : 7|10@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ ZEROS_BOH : 13|5@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ BRAKE_PUMP_REQUEST : 8|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ CRUISE_BOH2 : 23|3@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ CRUISE_OVERRIDE : 20|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ CRUISE_BOH3 : 19|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ CRUISE_FAULT_CMD : 18|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ CRUISE_CANCEL_CMD : 17|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ COMPUTER_BRAKE_REQUEST : 16|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ SET_ME_0X80 : 31|8@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ BRAKE_LIGHTS : 39|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ CRUISE_STATES : 38|7@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ CHIME : 47|3@0+ (1,0) [0|7] "" EBCM
|
||||
SG_ ZEROS_BOH6 : 44|1@0+ (1,0) [0|1] "" EBCM
|
||||
SG_ FCW : 43|2@0+ (1,0) [0|3] "" EBCM
|
||||
SG_ ZEROS_BOH4 : 55|8@0+ (1,0) [0|0] "" EBCM
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EBCM
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EBCM
|
||||
|
||||
BO_ 597 ROUGH_WHEEL_SPEED: 8 VSA
|
||||
SG_ WHEEL_SPEED_FL : 7|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ WHEEL_SPEED_FR : 15|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ WHEEL_SPEED_RL : 23|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ WHEEL_SPEED_RR : 31|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ SET_TO_X55 : 39|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ SET_TO_X55_2 : 47|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 773 SEATBELT_STATUS: 7 BDY
|
||||
SG_ SEATBELT_DRIVER_LAMP : 7|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ SEATBELT_PASS_UNLATCHED : 10|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ SEATBELT_PASS_LATCHED : 11|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 12|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ SEATBELT_DRIVER_LATCHED : 13|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ PASS_AIRBAG_OFF : 14|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ PASS_AIRBAG_ON : 15|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 777 LOCK_STATUS: 8 XXX
|
||||
SG_ DOORS_UNLOCKED : 54|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ DOORS_LOCKED : 55|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 780 ACC_HUD: 8 ADAS
|
||||
SG_ PCM_SPEED : 7|16@0+ (0.01,0) [0|250] "kph" BDY
|
||||
SG_ PCM_GAS : 23|8@0+ (1,0) [0|127] "" BDY
|
||||
SG_ CRUISE_SPEED : 31|8@0+ (1,0) [0|255] "" BDY
|
||||
SG_ DTC_MODE : 39|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ BOH : 38|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ ACC_PROBLEM : 37|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ FCM_OFF : 36|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ BOH_2 : 35|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ FCM_PROBLEM : 34|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ RADAR_OBSTRUCTED : 33|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ ENABLE_MINI_CAR : 32|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ SET_ME_X03 : 47|2@0+ (1,0) [0|3] "" BDY
|
||||
SG_ HUD_LEAD : 45|2@0+ (1,0) [0|3] "" BDY
|
||||
SG_ BOH_3 : 43|1@0+ (1,0) [0|3] "" BDY
|
||||
SG_ BOH_4 : 42|1@0+ (1,0) [0|3] "" BDY
|
||||
SG_ BOH_5 : 41|1@0+ (1,0) [0|3] "" BDY
|
||||
SG_ CRUISE_CONTROL_LABEL : 40|1@0+ (1,0) [0|3] "" BDY
|
||||
SG_ HUD_DISTANCE_3 : 52|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ SET_ME_X03_2 : 55|2@0+ (1,0) [0|3] "" BDY
|
||||
SG_ SET_ME_X01 : 48|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" BDY
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" BDY
|
||||
|
||||
BO_ 804 CRUISE: 8 PCM
|
||||
SG_ HUD_SPEED_KPH : 7|8@0+ (1,0) [0|255] "kph" EON
|
||||
SG_ HUD_SPEED_MPH : 15|8@0+ (1,0) [0|255] "mph" EON
|
||||
SG_ TRIP_FUEL_CONSUMED : 23|16@0+ (1,0) [0|255] "" EON
|
||||
SG_ CRUISE_SPEED_PCM : 39|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ BOH2 : 47|8@0- (1,0) [0|255] "" EON
|
||||
SG_ BOH3 : 55|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 829 LKAS_HUD: 5 ADAS
|
||||
SG_ CAM_TEMP_HIGH : 7|1@0+ (1,0) [0|255] "" BDY
|
||||
SG_ SET_ME_X41 : 6|7@0+ (1,0) [0|127] "" BDY
|
||||
SG_ BOH : 6|7@0+ (1,0) [0|127] "" BDY
|
||||
SG_ DASHED_LANES : 14|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ DTC : 13|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LKAS_PROBLEM : 12|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LKAS_OFF : 11|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ SOLID_LANES : 10|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LDW_RIGHT : 9|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ STEERING_REQUIRED : 8|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ BOH : 23|2@0+ (1,0) [0|4] "" BDY
|
||||
SG_ LDW_PROBLEM : 21|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ BEEP : 17|2@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LDW_ON : 28|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ LDW_OFF : 27|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ CLEAN_WINDSHIELD : 26|1@0+ (1,0) [0|1] "" BDY
|
||||
SG_ SET_ME_X48 : 31|8@0+ (1,0) [0|255] "" BDY
|
||||
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" BDY
|
||||
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" BDY
|
||||
|
||||
BO_ 892 CRUISE_PARAMS: 8 PCM
|
||||
SG_ CRUISE_SPEED_OFFSET : 31|8@0- (0.1,0) [-128|127] "kph" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 1029 DOORS_STATUS: 8 BDY
|
||||
SG_ DOOR_OPEN_FL : 37|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ DOOR_OPEN_FR : 38|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ DOOR_OPEN_RL : 39|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ DOOR_OPEN_RR : 40|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ TRUNK_OPEN : 41|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
CM_ SG_ 490 LONG_ACCEL "wheel speed derivative, noisy and zero snapping";
|
||||
CM_ SG_ 773 PASS_AIRBAG_ON "Might just be indicator light";
|
||||
CM_ SG_ 773 PASS_AIRBAG_OFF "Might just be indicator light";
|
||||
CM_ SG_ 780 CRUISE_SPEED "255 = no speed";
|
||||
CM_ SG_ 804 CRUISE_SPEED_PCM "255 = no speed";
|
||||
CM_ SG_ 829 BEEP "beeps are pleasant, chimes are for warnngs etc...";
|
||||
|
||||
|
||||
VAL_ 506 FCW 3 "fcw" 2 "fcw" 1 "fcw" 0 "no_fcw" ;
|
||||
VAL_ 506 CHIME 4 "double_chime" 3 "single_chime" 2 "continuous_chime" 1 "repeating_chime" 0 "no_chime" ;
|
||||
VAL_ 780 CRUISE_SPEED 255 "no_speed" 252 "stopped" ;
|
||||
VAL_ 780 HUD_LEAD 3 "acc_off" 2 "solid_car" 1 "dashed_car" 0 "no_car" ;
|
||||
VAL_ 829 BEEP 3 "single_beep" 2 "triple_beep" 1 "repeated_beep" 0 "no_beep" ;
|
||||
|
||||
CM_ "honda_fit_ex_2018_can.dbc starts here"
|
||||
|
||||
|
||||
|
||||
BO_ 145 KINEMATICS: 8 XXX
|
||||
SG_ LAT_ACCEL : 7|10@0+ (0.02,-512) [-20|20] "m/s2" EON
|
||||
|
||||
BO_ 228 STEERING_CONTROL: 5 ADAS
|
||||
SG_ STEER_TORQUE : 7|16@0- (1,0) [-3840|3840] "" EPS
|
||||
SG_ STEER_TORQUE_REQUEST : 23|1@0+ (1,0) [0|1] "" EPS
|
||||
SG_ SET_ME_X00 : 22|7@0+ (1,0) [0|127] "" EPS
|
||||
SG_ SET_ME_X00_2 : 31|8@0+ (1,0) [0|0] "" EPS
|
||||
SG_ COUNTER : 37|2@0+ (1,0) [0|3] "" EPS
|
||||
SG_ CHECKSUM : 35|4@0+ (1,0) [0|15] "" EPS
|
||||
|
||||
BO_ 304 GAS_PEDAL_2: 8 PCM
|
||||
SG_ ENGINE_TORQUE_ESTIMATE : 7|16@0- (1,0) [-1000|1000] "Nm" EON
|
||||
SG_ ENGINE_TORQUE_REQUEST : 23|16@0- (1,0) [-1000|1000] "Nm" EON
|
||||
SG_ CAR_GAS : 39|8@0+ (1,0) [0|255] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 342 STEERING_SENSORS: 6 EPS
|
||||
SG_ STEER_ANGLE : 7|16@0- (-0.1,0) [-500|500] "deg" EON
|
||||
SG_ STEER_ANGLE_RATE : 23|16@0- (1,0) [-3000|3000] "deg/s" EON
|
||||
SG_ COUNTER : 45|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 43|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 399 STEER_STATUS: 7 EPS
|
||||
SG_ STEER_TORQUE_SENSOR : 7|16@0- (1,0) [-31000|31000] "tbd" EON
|
||||
SG_ STEER_TORQUE_MOTOR : 23|16@0- (1,0) [-31000|31000] "tbd" EON
|
||||
SG_ STEER_STATUS : 39|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ STEER_CONTROL_ACTIVE : 35|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 53|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 51|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 401 GEARBOX: 8 PCM
|
||||
SG_ GEAR_SHIFTER : 5|6@0+ (1,0) [0|63] "" EON
|
||||
SG_ GEAR : 43|4@0+ (1,0) [0|15] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 420 VSA_STATUS: 8 VSA
|
||||
SG_ USER_BRAKE : 7|16@0+ (0.015625,-1.609375) [0|1000] "" EON
|
||||
SG_ ESP_DISABLED : 28|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_HOLD_ACTIVE : 46|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ BRAKE_HOLD_ENABLED : 45|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 422 SCM_BUTTONS: 8 SCM
|
||||
SG_ CRUISE_BUTTONS : 7|3@0+ (1,0) [0|7] "" EON
|
||||
SG_ LIGHTS_SETTING : 1|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ MAIN_ON : 47|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ CRUISE_SETTING : 43|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 487 BRAKE_PRESSURE: 4 VSA
|
||||
SG_ BRAKE_PRESSURE1 : 7|10@0+ (0.015625,-103) [0|1000] "" EON
|
||||
SG_ BRAKE_PRESSURE2 : 9|10@0+ (0.015625,-103) [0|1000] "" EON
|
||||
SG_ CHECKSUM : 27|4@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 29|2@0+ (1,0) [0|3] "" EON
|
||||
|
||||
BO_ 660 SCM_FEEDBACK: 8 SCM
|
||||
SG_ RIGHT_BLINKER : 6|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ LEFT_BLINKER : 5|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ WIPERS_SPEED : 4|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" EON
|
||||
|
||||
BO_ 862 HIGHBEAM_CONTROL: 8 ADAS
|
||||
SG_ ZEROS_BOH : 7|50@0+ (1,0) [0|127] "" BDY
|
||||
SG_ ZEROS_BOH_2 : 48|4@1+ (1,0) [0|15] "" XXX
|
||||
SG_ HIGHBEAMS_ON : 52|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ AUTO_HIGHBEAMS_ACTIVE : 53|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 884 STALK_STATUS: 8 XXX
|
||||
SG_ AUTO_HEADLIGHTS : 46|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ HIGH_BEAM_HOLD : 47|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ HIGH_BEAM_FLASH : 45|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ HEADLIGHTS_ON : 54|1@0+ (1,0) [0|1] "" EON
|
||||
SG_ CHECKSUM : 59|4@0+ (1,0) [0|3] "" EON
|
||||
SG_ COUNTER : 61|2@0+ (1,0) [0|3] "" EON
|
||||
|
||||
CM_ SG_ 401 GEAR "10 = reverse, 11 = transition";
|
||||
CM_ SG_ 420 BRAKE_HOLD_RELATED "On when Brake Hold engaged";
|
||||
|
||||
VAL_ 399 STEER_STATUS 5 "fault" 4 "no_torque_alert_2" 2 "no_torque_alert_1" 0 "normal" ;
|
||||
VAL_ 401 GEAR_SHIFTER 32 "L" 16 "S" 8 "D" 4 "N" 2 "R" 1 "P" ;
|
||||
VAL_ 401 GEAR 7 "L" 10 "S" 4 "D" 3 "N" 2 "R" 1 "P" ;
|
||||
VAL_ 422 CRUISE_BUTTONS 7 "tbd" 6 "tbd" 5 "tbd" 4 "accel_res" 3 "decel_set" 2 "cancel" 1 "main" 0 "none" ;
|
||||
VAL_ 422 LIGHTS_SETTING 3 "high_beam" 2 "low_beam" 1 "position" 0 "no_lights" ;
|
||||
VAL_ 422 CRUISE_SETTING 3 "distance_adj" 2 "tbd" 1 "lkas_button" 0 "none" ;
|
||||
|
||||
CM_ "CHFFR_METRIC 342 STEER_ANGLE STEER_ANGLE 0.36 180; CHFFR_METRIC 380 ENGINE_RPM ENGINE_RPM 1 0; CHFFR_METRIC 804 ENGINE_TEMPERATURE ENGINE_TEMPERATURE 1 0";
|
File diff suppressed because it is too large
Load Diff
|
@ -0,0 +1,247 @@
|
|||
CM_ "AUTOGENERATED FILE, DO NOT EDIT"
|
||||
|
||||
|
||||
CM_ "Imported file _comma.dbc starts here"
|
||||
BO_ 359 STEERING_IPAS_COMMA: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM BO_ STEERING_IPAS_COMMA "Copy of msg 614 so we can do angle control while the Park Assist ECU is connected (Panda spoofs 614 with 359 on connector J70). Note that addresses 0x266 and 0x167 are checksum-invariant";
|
||||
|
||||
|
||||
CM_ "Imported file _toyota_2017.dbc starts here"
|
||||
VERSION ""
|
||||
|
||||
|
||||
NS_ :
|
||||
NS_DESC_
|
||||
CM_
|
||||
BA_DEF_
|
||||
BA_
|
||||
VAL_
|
||||
CAT_DEF_
|
||||
CAT_
|
||||
FILTER
|
||||
BA_DEF_DEF_
|
||||
EV_DATA_
|
||||
ENVVAR_DATA_
|
||||
SGTYPE_
|
||||
SGTYPE_VAL_
|
||||
BA_DEF_SGTYPE_
|
||||
BA_SGTYPE_
|
||||
SIG_TYPE_REF_
|
||||
VAL_TABLE_
|
||||
SIG_GROUP_
|
||||
SIG_VALTYPE_
|
||||
SIGTYPE_VALTYPE_
|
||||
BO_TX_BU_
|
||||
BA_DEF_REL_
|
||||
BA_REL_
|
||||
BA_DEF_DEF_REL_
|
||||
BU_SG_REL_
|
||||
BU_EV_REL_
|
||||
BU_BO_REL_
|
||||
SG_MUL_VAL_
|
||||
|
||||
BS_:
|
||||
|
||||
BU_: XXX DSU HCU EPS IPAS
|
||||
|
||||
BO_ 36 KINEMATICS: 8 XXX
|
||||
SG_ ACCEL_Y : 33|10@0+ (1,-512) [0|65535] "" XXX
|
||||
SG_ YAW_RATE : 1|10@0+ (1,-512) [0|65535] "" XXX
|
||||
SG_ STEERING_TORQUE : 17|10@0+ (1,-512) [0|65535] "" XXX
|
||||
|
||||
BO_ 166 BRAKE: 8 XXX
|
||||
SG_ BRAKE_AMOUNT : 7|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ BRAKE_PEDAL : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 170 WHEEL_SPEEDS: 8 XXX
|
||||
SG_ WHEEL_SPEED_FR : 7|16@0+ (0.01,-67.67) [0|250] "kph" XXX
|
||||
SG_ WHEEL_SPEED_FL : 23|16@0+ (0.01,-67.67) [0|250] "kph" XXX
|
||||
SG_ WHEEL_SPEED_RR : 39|16@0+ (0.01,-67.67) [0|250] "kph" XXX
|
||||
SG_ WHEEL_SPEED_RL : 55|16@0+ (0.01,-67.67) [0|250] "kph" XXX
|
||||
|
||||
BO_ 180 SPEED: 8 XXX
|
||||
SG_ ENCODER : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SPEED : 47|16@0+ (0.01,0) [0|250] "kph" XXX
|
||||
|
||||
BO_ 466 PCM_CRUISE: 8 XXX
|
||||
SG_ GAS_RELEASED : 4|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ STANDSTILL_ON : 12|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ACCEL_NET : 23|16@0- (0.001,0) [-20|20] "m/s2" XXX
|
||||
SG_ CRUISE_STATE : 55|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 552 ACCELEROMETER: 8 XXX
|
||||
SG_ ACCEL_Z : 22|15@0- (1,0) [0|32767] "" XXX
|
||||
SG_ ACCEL_X : 6|15@0- (0.001,0) [-20|20] "m/s2" XXX
|
||||
|
||||
BO_ 560 BRAKE_MODULE2: 7 XXX
|
||||
SG_ BRAKE_PRESSED : 26|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 614 STEERING_IPAS: 8 IPAS
|
||||
SG_ STATE : 7|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ ANGLE : 3|12@0- (1.5,0) [-510|510] "deg" XXX
|
||||
SG_ SET_ME_X10 : 23|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ DIRECTION_CMD : 38|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X40 : 47|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ SET_ME_X00 : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 643 PRE_COLLISION: 8 XXX
|
||||
|
||||
BO_ 740 STEERING_LKA: 5 XXX
|
||||
SG_ LKA_STATE : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ STEER_REQUEST : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ COUNTER : 6|6@0+ (1,0) [0|63] "" XXX
|
||||
SG_ SET_ME_1 : 7|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ STEER_TORQUE_CMD : 15|16@0- (1,0) [0|65535] "" XXX
|
||||
SG_ CHECKSUM : 39|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 742 LEAD_INFO: 8 DSU
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" HCU
|
||||
SG_ LEAD_REL_SPEED : 23|12@0- (0.025,0) [-100|100] "m/s" HCU
|
||||
SG_ LEAD_LONG_DIST : 7|13@0+ (0.05,0) [0|300] "m" HCU
|
||||
|
||||
BO_ 835 ACC_CONTROL: 8 DSU
|
||||
SG_ ACCEL_CMD : 7|16@0- (0.001,0) [-20|20] "m/s2" HCU
|
||||
SG_ SET_ME_X63 : 23|8@0+ (1,0) [0|255] "" HCU
|
||||
SG_ SET_ME_1 : 30|1@0+ (1,0) [0|1] "" HCU
|
||||
SG_ RELEASE_STANDSTILL : 31|1@0+ (1,0) [0|1] "" HCU
|
||||
SG_ CANCEL_REQ : 24|1@0+ (1,0) [0|1] "" HCU
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 1556 STEERING_LEVERS: 8 XXX
|
||||
SG_ TURN_SIGNALS : 29|2@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 37 STEER_ANGLE_SENSOR: 8 XXX
|
||||
SG_ STEER_ANGLE : 3|12@0- (1.5,0) [-500|500] "deg" XXX
|
||||
SG_ STEER_FRACTION : 39|4@0- (0.1,0) [-0.7|0.7] "deg" XXX
|
||||
SG_ STEER_RATE : 35|12@0- (1,0) [-2000|2000] "deg/s" XXX
|
||||
|
||||
BO_ 467 PCM_CRUISE_2: 8 XXX
|
||||
SG_ MAIN_ON : 15|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LOW_SPEED_LOCKOUT : 14|2@0+ (1,0) [0|3] "kph" XXX
|
||||
SG_ SET_SPEED : 23|8@0+ (1,0) [0|255] "kph" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 921 PCM_CRUISE_SM: 8 XXX
|
||||
SG_ MAIN_ON : 4|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CRUISE_CONTROL_STATE : 11|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ UI_SET_SPEED : 31|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 951 ESP_CONTROL: 8 ESP
|
||||
SG_ TC_DISABLED : 13|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ BRAKE_LIGHTS_ACC : 18|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1041 ACC_HUD: 8 DSU
|
||||
SG_ FCW : 4|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X20 : 15|8@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X10 : 39|8@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X80 : 55|8@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1042 LKAS_HUD: 8 XXX
|
||||
SG_ BARRIERS : 1|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ RIGHT_LINE : 3|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ LEFT_LINE : 5|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X01 : 7|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ SET_ME_X01_2 : 11|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ LDA_ALERT : 9|2@0+ (1,0) [0|3] "" XXX
|
||||
SG_ TWO_BEEPS : 12|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ ADJUSTING_CAMERA : 13|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ LDA_MALFUNCTION : 15|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ REPEATED_BEEPS : 32|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X0C : 23|8@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X2C : 47|8@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X38 : 55|8@0+ (1,0) [0|1] "" XXX
|
||||
SG_ SET_ME_X02 : 63|8@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1553 UI_SEETING: 8 XXX
|
||||
SG_ UNITS : 26|2@0+ (1,0) [0|3] "" XXX
|
||||
|
||||
BO_ 1568 SEATS_DOORS: 8 XXX
|
||||
SG_ SEATBELT_DRIVER_UNLATCHED : 62|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FL : 45|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RL : 42|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_RR : 43|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ DOOR_OPEN_FR : 44|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 1570 LIGHT_STALK: 8 SCM
|
||||
SG_ AUTO_HIGH_BEAM : 37|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
CM_ SG_ 36 ACCEL_Y "unit is tbd";
|
||||
CM_ SG_ 36 YAW_RATE "verify";
|
||||
CM_ SG_ 36 STEERING_TORQUE "does not seem the steer torque, tbd";
|
||||
CM_ SG_ 466 ACCEL_NET "net acceleration produced by the system, given ACCEL_CMD, road grade and other factors";
|
||||
CM_ SG_ 560 BRAKE_PRESSED "another brake pressed?";
|
||||
CM_ SG_ 951 BRAKE_LIGHTS_ACC "brake lights when ACC commands decel";
|
||||
CM_ SG_ 608 STEER_TORQUE_DRIVER "driver torque";
|
||||
CM_ SG_ 608 STEER_OVERRIDE "set when driver torque exceeds a certain value";
|
||||
CM_ SG_ 614 ANGLE "set to measured angle when ipas control isn't active";
|
||||
CM_ SG_ 37 STEER_FRACTION "1/15th of the signal STEER_ANGLE, which is 1.5 deg; note that 0x8 is never set";
|
||||
CM_ SG_ 37 STEER_RATE "factor is tbd";
|
||||
CM_ SG_ 467 SET_SPEED "43 kph are shown as 28mph, so conversion isnt perfect";
|
||||
CM_ SG_ 467 LOW_SPEED_LOCKOUT "in low speed lockout, system would always disengage below 28mph";
|
||||
CM_ SG_ 921 UI_SET_SPEED "set speed shown in UI with user set unit";
|
||||
CM_ SG_ 1042 SET_ME_1 "unclear what this is, but it's always 1 in drive traces";
|
||||
CM_ SG_ 1042 REPEATED_BEEPS "recommended for fcw and other important alerts";
|
||||
VAL_ 466 CRUISE_STATE 8 "active" 7 "standstill" 1 "off" ;
|
||||
VAL_ 467 LOW_SPEED_LOCKOUT 2 "low speed locked" 1 "ok" ;
|
||||
VAL_ 614 STATE 3 "enabled" 1 "disabled";
|
||||
VAL_ 614 DIRECTION_CMD 3 "right" 2 "center" 1 "left";
|
||||
VAL_ 1553 UNITS 1 "km" 2 "miles";
|
||||
VAL_ 1556 TURN_SIGNALS 3 "none" 2 "right" 1 "left" ;
|
||||
VAL_ 1042 LDA_ALERT 3 "hold with continuous beep" 2 "LDA unavailable" 1 "hold" 0 "none";
|
||||
VAL_ 1042 BARRIERS 3 "both" 2 "right" 1 "left" 0 "none";
|
||||
VAL_ 1042 RIGHT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none";
|
||||
VAL_ 1042 LEFT_LINE 3 "orange" 2 "double" 1 "solid" 0 "none";
|
||||
VAL_ 921 CRUISE_CONTROL_STATE 2 "disabled" 11 "hold" 10 "hold_waiting_user_cmd" 6 "enabled" 5 "faulted";
|
||||
|
||||
CM_ "CHFFR_METRIC 37 STEER_ANGLE STEER_ANGLE 0.36 180";
|
||||
|
||||
CM_ "toyota_chr_hybrid_2018_pt.dbc starts here"
|
||||
|
||||
|
||||
|
||||
BO_ 295 GEAR_PACKET: 8 XXX
|
||||
SG_ CAR_MOVEMENT : 39|8@0- (1,0) [0|255] "" XXX
|
||||
SG_ COUNTER : 55|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
SG_ GEAR : 47|4@0+ (1,0) [0|15] "" XXX
|
||||
|
||||
BO_ 550 BRAKE_MODULE: 8 XXX
|
||||
SG_ BRAKE_PRESSURE : 0|9@0+ (1,0) [0|511] "" XXX
|
||||
SG_ BRAKE_POSITION : 16|9@0+ (1,0) [0|511] "" XXX
|
||||
SG_ BRAKE_PRESSED : 37|1@0+ (1,0) [0|1] "" XXX
|
||||
|
||||
BO_ 581 GAS_PEDAL: 8 XXX
|
||||
SG_ GAS_PEDAL : 23|8@0+ (0.005,0) [0|1] "" XXX
|
||||
|
||||
BO_ 608 STEER_TORQUE_SENSOR: 8 XXX
|
||||
SG_ STEER_TORQUE_EPS : 47|16@0- (0.73,0) [-20000|20000] "" XXX
|
||||
SG_ STEER_TORQUE_DRIVER : 15|16@0- (1,0) [-32768|32767] "" XXX
|
||||
SG_ STEER_OVERRIDE : 0|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
BO_ 610 EPS_STATUS: 8 EPS
|
||||
SG_ IPAS_STATE : 3|4@0+ (1,0) [0|15] "" XXX
|
||||
SG_ LKA_STATE : 31|7@0+ (1,0) [0|127] "" XXX
|
||||
SG_ TYPE : 24|1@0+ (1,0) [0|1] "" XXX
|
||||
SG_ CHECKSUM : 63|8@0+ (1,0) [0|255] "" XXX
|
||||
|
||||
CM_ SG_ 548 BRAKE_PRESSURE "seems prop to pedal force";
|
||||
CM_ SG_ 548 BRAKE_POSITION "seems proportional to pedal displacement, unclear the max value of 0x1c8";
|
||||
CM_ SG_ 610 TYPE "seems 1 on Corolla, 0 on all others";
|
||||
CM_ SG_ 581 GAS_PEDAL "it seems slightly filtered";
|
||||
VAL_ 295 GEAR 0 "P" 1 "R" 2 "N" 3 "D" 4 "B";
|
||||
VAL_ 610 IPAS_STATE 5 "override" 3 "enabled" 1 "disabled";
|
||||
VAL_ 610 LKA_STATE 25 "temporary_fault" 9 "temporary_fault2" 5 "active" 1 "standby";
|
|
@ -1 +1 @@
|
|||
v1.1.2
|
||||
v1.1.3
|
|
@ -1,32 +1,34 @@
|
|||
struct sample_t torque_meas; // last 3 motor torques produced by the eps
|
||||
int toyota_no_dsu_car = 0; // ch-r and camry don't have the DSU
|
||||
int toyota_giraffe_switch_1 = 0; // is giraffe switch 1 high?
|
||||
|
||||
// global torque limit
|
||||
const int MAX_TORQUE = 1500; // max torque cmd allowed ever
|
||||
const int TOYOTA_MAX_TORQUE = 1500; // max torque cmd allowed ever
|
||||
|
||||
// rate based torque limit + stay within actually applied
|
||||
// packet is sent at 100hz, so this limit is 1000/sec
|
||||
const int MAX_RATE_UP = 10; // ramp up slow
|
||||
const int MAX_RATE_DOWN = 25; // ramp down fast
|
||||
const int MAX_TORQUE_ERROR = 350; // max torque cmd in excess of torque motor
|
||||
const int TOYOTA_MAX_RATE_UP = 10; // ramp up slow
|
||||
const int TOYOTA_MAX_RATE_DOWN = 25; // ramp down fast
|
||||
const int TOYOTA_MAX_TORQUE_ERROR = 350; // max torque cmd in excess of torque motor
|
||||
|
||||
// real time torque limit to prevent controls spamming
|
||||
// the real time limit is 1500/sec
|
||||
const int MAX_RT_DELTA = 375; // max delta torque allowed for real time checks
|
||||
const int RT_INTERVAL = 250000; // 250ms between real time checks
|
||||
const int TOYOTA_MAX_RT_DELTA = 375; // max delta torque allowed for real time checks
|
||||
const int TOYOTA_RT_INTERVAL = 250000; // 250ms between real time checks
|
||||
|
||||
// longitudinal limits
|
||||
const int MAX_ACCEL = 1500; // 1.5 m/s2
|
||||
const int MIN_ACCEL = -3000; // 3.0 m/s2
|
||||
const int TOYOTA_MAX_ACCEL = 1500; // 1.5 m/s2
|
||||
const int TOYOTA_MIN_ACCEL = -3000; // 3.0 m/s2
|
||||
|
||||
// global actuation limit state
|
||||
int actuation_limits = 1; // by default steer limits are imposed
|
||||
int dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file
|
||||
int toyota_actuation_limits = 1; // by default steer limits are imposed
|
||||
int toyota_dbc_eps_torque_factor = 100; // conversion factor for STEER_TORQUE_EPS in %: see dbc file
|
||||
|
||||
// state of torque limits
|
||||
int desired_torque_last = 0; // last desired steer torque
|
||||
int rt_torque_last = 0; // last desired torque for real time check
|
||||
uint32_t ts_last = 0;
|
||||
int cruise_engaged_last = 0; // cruise state
|
||||
int toyota_desired_torque_last = 0; // last desired steer torque
|
||||
int toyota_rt_torque_last = 0; // last desired torque for real time check
|
||||
uint32_t toyota_ts_last = 0;
|
||||
int toyota_cruise_engaged_last = 0; // cruise state
|
||||
struct sample_t toyota_torque_meas; // last 3 motor torques produced by the eps
|
||||
|
||||
|
||||
static void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
||||
|
@ -36,26 +38,38 @@ static void toyota_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
|||
torque_meas_new = to_signed(torque_meas_new, 16);
|
||||
|
||||
// scale by dbc_factor
|
||||
torque_meas_new = (torque_meas_new * dbc_eps_torque_factor) / 100;
|
||||
torque_meas_new = (torque_meas_new * toyota_dbc_eps_torque_factor) / 100;
|
||||
|
||||
// increase torque_meas by 1 to be conservative on rounding
|
||||
torque_meas_new += (torque_meas_new > 0 ? 1 : -1);
|
||||
|
||||
// update array of sample
|
||||
update_sample(&torque_meas, torque_meas_new);
|
||||
update_sample(&toyota_torque_meas, torque_meas_new);
|
||||
}
|
||||
|
||||
// enter controls on rising edge of ACC, exit controls on ACC off
|
||||
if ((to_push->RIR>>21) == 0x1D2) {
|
||||
// 4 bits: 55-52
|
||||
int cruise_engaged = to_push->RDHR & 0xF00000;
|
||||
if (cruise_engaged && !cruise_engaged_last) {
|
||||
if (cruise_engaged && !toyota_cruise_engaged_last) {
|
||||
controls_allowed = 1;
|
||||
} else if (!cruise_engaged) {
|
||||
controls_allowed = 0;
|
||||
}
|
||||
cruise_engaged_last = cruise_engaged;
|
||||
toyota_cruise_engaged_last = cruise_engaged;
|
||||
}
|
||||
|
||||
int bus = (to_push->RDTR >> 4) & 0xF;
|
||||
// 0x680 is a radar msg only found in dsu-less cars
|
||||
if ((to_push->RIR>>21) == 0x680 && (bus == 1)) {
|
||||
toyota_no_dsu_car = 1;
|
||||
}
|
||||
|
||||
// 0x2E4 is lkas cmd. If it is on bus 0, then giraffe switch 1 is high
|
||||
if ((to_push->RIR>>21) == 0x2E4 && (bus == 0)) {
|
||||
toyota_giraffe_switch_1 = 1;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
|
||||
|
@ -70,8 +84,8 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
|
|||
if ((to_send->RIR>>21) == 0x343) {
|
||||
int desired_accel = ((to_send->RDLR & 0xFF) << 8) | ((to_send->RDLR >> 8) & 0xFF);
|
||||
desired_accel = to_signed(desired_accel, 16);
|
||||
if (controls_allowed && actuation_limits) {
|
||||
int violation = max_limit_check(desired_accel, MAX_ACCEL, MIN_ACCEL);
|
||||
if (controls_allowed && toyota_actuation_limits) {
|
||||
int violation = max_limit_check(desired_accel, TOYOTA_MAX_ACCEL, TOYOTA_MIN_ACCEL);
|
||||
if (violation) return 0;
|
||||
} else if (!controls_allowed && (desired_accel != 0)) {
|
||||
return 0;
|
||||
|
@ -87,25 +101,26 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
|
|||
uint32_t ts = TIM2->CNT;
|
||||
|
||||
// only check if controls are allowed and actuation_limits are imposed
|
||||
if (controls_allowed && actuation_limits) {
|
||||
if (controls_allowed && toyota_actuation_limits) {
|
||||
|
||||
// *** global torque limit check ***
|
||||
violation |= max_limit_check(desired_torque, MAX_TORQUE, -MAX_TORQUE);
|
||||
violation |= max_limit_check(desired_torque, TOYOTA_MAX_TORQUE, -TOYOTA_MAX_TORQUE);
|
||||
|
||||
// *** torque rate limit check ***
|
||||
violation |= dist_to_meas_check(desired_torque, desired_torque_last, &torque_meas, MAX_RATE_UP, MAX_RATE_DOWN, MAX_TORQUE_ERROR);
|
||||
violation |= dist_to_meas_check(desired_torque, toyota_desired_torque_last,
|
||||
&toyota_torque_meas, TOYOTA_MAX_RATE_UP, TOYOTA_MAX_RATE_DOWN, TOYOTA_MAX_TORQUE_ERROR);
|
||||
|
||||
// used next time
|
||||
desired_torque_last = desired_torque;
|
||||
toyota_desired_torque_last = desired_torque;
|
||||
|
||||
// *** torque real time rate limit check ***
|
||||
violation |= rt_rate_limit_check(desired_torque, rt_torque_last, MAX_RT_DELTA);
|
||||
violation |= rt_rate_limit_check(desired_torque, toyota_rt_torque_last, TOYOTA_MAX_RT_DELTA);
|
||||
|
||||
// every RT_INTERVAL set the new limits
|
||||
uint32_t ts_elapsed = get_ts_elapsed(ts, ts_last);
|
||||
if (ts_elapsed > RT_INTERVAL) {
|
||||
rt_torque_last = desired_torque;
|
||||
ts_last = ts;
|
||||
uint32_t ts_elapsed = get_ts_elapsed(ts, toyota_ts_last);
|
||||
if (ts_elapsed > TOYOTA_RT_INTERVAL) {
|
||||
toyota_rt_torque_last = desired_torque;
|
||||
toyota_ts_last = ts;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -116,9 +131,9 @@ static int toyota_tx_hook(CAN_FIFOMailBox_TypeDef *to_send) {
|
|||
|
||||
// reset to 0 if either controls is not allowed or there's a violation
|
||||
if (violation || !controls_allowed) {
|
||||
desired_torque_last = 0;
|
||||
rt_torque_last = 0;
|
||||
ts_last = ts;
|
||||
toyota_desired_torque_last = 0;
|
||||
toyota_rt_torque_last = 0;
|
||||
toyota_ts_last = ts;
|
||||
}
|
||||
|
||||
if (violation) {
|
||||
|
@ -138,11 +153,19 @@ static int toyota_tx_lin_hook(int lin_num, uint8_t *data, int len) {
|
|||
|
||||
static void toyota_init(int16_t param) {
|
||||
controls_allowed = 0;
|
||||
actuation_limits = 1;
|
||||
dbc_eps_torque_factor = param;
|
||||
toyota_actuation_limits = 1;
|
||||
toyota_giraffe_switch_1 = 0;
|
||||
toyota_dbc_eps_torque_factor = param;
|
||||
}
|
||||
|
||||
static int toyota_fwd_hook(int bus_num, CAN_FIFOMailBox_TypeDef *to_fwd) {
|
||||
|
||||
// forward cam to radar and viceversa if car is dsu-less, except lkas cmd and hud
|
||||
if ((bus_num == 0 || bus_num == 2) && toyota_no_dsu_car && !toyota_giraffe_switch_1) {
|
||||
int addr = to_fwd->RIR>>21;
|
||||
bool is_lkas_msg = (addr == 0x2E4 || addr == 0x412) && bus_num == 2;
|
||||
return is_lkas_msg? -1 : (uint8_t)(~bus_num & 0x2);
|
||||
}
|
||||
return -1;
|
||||
}
|
||||
|
||||
|
@ -157,8 +180,9 @@ const safety_hooks toyota_hooks = {
|
|||
|
||||
static void toyota_nolimits_init(int16_t param) {
|
||||
controls_allowed = 0;
|
||||
actuation_limits = 0;
|
||||
dbc_eps_torque_factor = param;
|
||||
toyota_actuation_limits = 0;
|
||||
toyota_giraffe_switch_1 = 0;
|
||||
toyota_dbc_eps_torque_factor = param;
|
||||
}
|
||||
|
||||
const safety_hooks toyota_nolimits_hooks = {
|
||||
|
|
|
@ -2,7 +2,7 @@
|
|||
// TODO: refactor to repeat less code
|
||||
|
||||
// IPAS override
|
||||
const int32_t IPAS_OVERRIDE_THRESHOLD = 200; // disallow controls when user torque exceeds this value
|
||||
const int32_t TOYOTA_IPAS_OVERRIDE_THRESHOLD = 200; // disallow controls when user torque exceeds this value
|
||||
|
||||
struct lookup_t {
|
||||
float x[3];
|
||||
|
@ -92,7 +92,7 @@ static void toyota_ipas_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
|||
|
||||
// every RT_INTERVAL or when controls are turned on, set the new limits
|
||||
uint32_t ts_elapsed = get_ts_elapsed(ts, ts_angle_last);
|
||||
if ((ts_elapsed > RT_INTERVAL) || (controls_allowed && !controls_allowed_last)) {
|
||||
if ((ts_elapsed > TOYOTA_RT_INTERVAL) || (controls_allowed && !controls_allowed_last)) {
|
||||
rt_angle_last = angle_meas_new;
|
||||
ts_angle_last = ts;
|
||||
}
|
||||
|
@ -118,8 +118,8 @@ static void toyota_ipas_rx_hook(CAN_FIFOMailBox_TypeDef *to_push) {
|
|||
}
|
||||
|
||||
// exit controls on high steering override
|
||||
if (angle_control && ((torque_driver.min > IPAS_OVERRIDE_THRESHOLD) ||
|
||||
(torque_driver.max < -IPAS_OVERRIDE_THRESHOLD) ||
|
||||
if (angle_control && ((torque_driver.min > TOYOTA_IPAS_OVERRIDE_THRESHOLD) ||
|
||||
(torque_driver.max < -TOYOTA_IPAS_OVERRIDE_THRESHOLD) ||
|
||||
(ipas_state==5))) {
|
||||
controls_allowed = 0;
|
||||
}
|
||||
|
|
|
@ -29,11 +29,11 @@ def tesla_tester():
|
|||
|
||||
# BDY 0x248 is the MCU_commands message, which includes folding mirrors, opening the trunk, frunk, setting the cars lock state and more. For our test, we will edit the 3rd byte, which is MCU_lockRequest. 0x01 will lock, 0x02 will unlock:
|
||||
print("Unlocking Tesla...")
|
||||
p.can_send(0x248, "\x00\x00\x02\x00\x00\x00\x00\x00", bus_num)
|
||||
p.can_send(0x248, "\x00\x00\x02\x00\x00\x00\x00\x00", body_bus_num)
|
||||
|
||||
#Or, we can set the first byte, MCU_frontHoodCommand + MCU_liftgateSwitch, to 0x01 to pop the frunk, or 0x04 to open/close the trunk (0x05 should open both)
|
||||
print("Opening Frunk...")
|
||||
p.can_send(0x248, "\x01\x00\x00\x00\x00\x00\x00\x00", bus_num)
|
||||
p.can_send(0x248, "\x01\x00\x00\x00\x00\x00\x00\x00", body_bus_num)
|
||||
|
||||
#Back to safety...
|
||||
print("Disabling output on Panda...")
|
||||
|
@ -41,7 +41,6 @@ def tesla_tester():
|
|||
|
||||
print("Reading VIN from 0x568. This is painfully slow and can take up to 3 minutes (1 minute per message; 3 messages needed for full VIN)...")
|
||||
|
||||
cnt = 0
|
||||
vin = {}
|
||||
while True:
|
||||
#Read the VIN
|
||||
|
@ -53,11 +52,10 @@ def tesla_tester():
|
|||
vin_string = binascii.hexlify(dat)[2:] #rest of the string is the actual VIN data
|
||||
vin[vin_index] = vin_string.decode("hex")
|
||||
print("Got VIN index " + str(vin_index) + " data " + vin[vin_index])
|
||||
cnt += 1
|
||||
#if we have all 3 parts of the VIN, print it and break out of our while loop
|
||||
if cnt == 3:
|
||||
if 0 in vin and 1 in vin and 2 in vin:
|
||||
print("VIN: " + vin[0] + vin[1] + vin[2][:3])
|
||||
break
|
||||
|
||||
if __name__ == "__main__":
|
||||
tesla_tester()
|
||||
tesla_tester()
|
||||
|
|
|
@ -38,13 +38,13 @@ void reset_angle_control(void);
|
|||
int get_controls_allowed(void);
|
||||
void init_tests_toyota(void);
|
||||
void set_timer(int t);
|
||||
void set_torque_meas(int min, int max);
|
||||
void set_toyota_torque_meas(int min, int max);
|
||||
void set_cadillac_torque_driver(int min, int max);
|
||||
void set_gm_torque_driver(int min, int max);
|
||||
void set_rt_torque_last(int t);
|
||||
void set_desired_torque_last(int t);
|
||||
int get_torque_meas_min(void);
|
||||
int get_torque_meas_max(void);
|
||||
void set_toyota_rt_torque_last(int t);
|
||||
void set_toyota_desired_torque_last(int t);
|
||||
int get_toyota_torque_meas_min(void);
|
||||
int get_toyota_torque_meas_max(void);
|
||||
|
||||
void init_tests_honda(void);
|
||||
int get_ego_speed(void);
|
||||
|
|
|
@ -22,7 +22,7 @@ typedef struct
|
|||
uint32_t CNT;
|
||||
} TIM_TypeDef;
|
||||
|
||||
struct sample_t torque_meas;
|
||||
struct sample_t toyota_torque_meas;
|
||||
struct sample_t cadillac_torque_driver;
|
||||
struct sample_t gm_torque_driver;
|
||||
|
||||
|
@ -60,9 +60,9 @@ void set_timer(int t){
|
|||
timer.CNT = t;
|
||||
}
|
||||
|
||||
void set_torque_meas(int min, int max){
|
||||
torque_meas.min = min;
|
||||
torque_meas.max = max;
|
||||
void set_toyota_torque_meas(int min, int max){
|
||||
toyota_torque_meas.min = min;
|
||||
toyota_torque_meas.max = max;
|
||||
}
|
||||
|
||||
void set_cadillac_torque_driver(int min, int max){
|
||||
|
@ -75,16 +75,16 @@ void set_gm_torque_driver(int min, int max){
|
|||
gm_torque_driver.max = max;
|
||||
}
|
||||
|
||||
int get_torque_meas_min(void){
|
||||
return torque_meas.min;
|
||||
int get_toyota_torque_meas_min(void){
|
||||
return toyota_torque_meas.min;
|
||||
}
|
||||
|
||||
int get_torque_meas_max(void){
|
||||
return torque_meas.max;
|
||||
int get_toyota_torque_meas_max(void){
|
||||
return toyota_torque_meas.max;
|
||||
}
|
||||
|
||||
void set_rt_torque_last(int t){
|
||||
rt_torque_last = t;
|
||||
void set_toyota_rt_torque_last(int t){
|
||||
toyota_rt_torque_last = t;
|
||||
}
|
||||
|
||||
void set_cadillac_rt_torque_last(int t){
|
||||
|
@ -95,8 +95,8 @@ void set_gm_rt_torque_last(int t){
|
|||
gm_rt_torque_last = t;
|
||||
}
|
||||
|
||||
void set_desired_torque_last(int t){
|
||||
desired_torque_last = t;
|
||||
void set_toyota_desired_torque_last(int t){
|
||||
toyota_desired_torque_last = t;
|
||||
}
|
||||
|
||||
void set_cadillac_desired_torque_last(int t){
|
||||
|
@ -129,11 +129,11 @@ void set_bosch_hardware(bool c){
|
|||
}
|
||||
|
||||
void init_tests_toyota(void){
|
||||
torque_meas.min = 0;
|
||||
torque_meas.max = 0;
|
||||
desired_torque_last = 0;
|
||||
rt_torque_last = 0;
|
||||
ts_last = 0;
|
||||
toyota_torque_meas.min = 0;
|
||||
toyota_torque_meas.max = 0;
|
||||
toyota_desired_torque_last = 0;
|
||||
toyota_rt_torque_last = 0;
|
||||
toyota_ts_last = 0;
|
||||
set_timer(0);
|
||||
}
|
||||
|
||||
|
|
|
@ -41,9 +41,9 @@ class TestToyotaSafety(unittest.TestCase):
|
|||
cls.safety.init_tests_toyota()
|
||||
|
||||
def _set_prev_torque(self, t):
|
||||
self.safety.set_desired_torque_last(t)
|
||||
self.safety.set_rt_torque_last(t)
|
||||
self.safety.set_torque_meas(t, t)
|
||||
self.safety.set_toyota_desired_torque_last(t)
|
||||
self.safety.set_toyota_rt_torque_last(t)
|
||||
self.safety.set_toyota_torque_meas(t, t)
|
||||
|
||||
def _torque_meas_msg(self, torque):
|
||||
to_send = libpandasafety_py.ffi.new('CAN_FIFOMailBox_TypeDef *')
|
||||
|
@ -158,9 +158,9 @@ class TestToyotaSafety(unittest.TestCase):
|
|||
for controls_allowed in [True, False]:
|
||||
for torque in np.arange(-MAX_TORQUE - 1000, MAX_TORQUE + 1000, MAX_RATE_UP):
|
||||
self.safety.set_controls_allowed(controls_allowed)
|
||||
self.safety.set_rt_torque_last(torque)
|
||||
self.safety.set_torque_meas(torque, torque)
|
||||
self.safety.set_desired_torque_last(torque - MAX_RATE_UP)
|
||||
self.safety.set_toyota_rt_torque_last(torque)
|
||||
self.safety.set_toyota_torque_meas(torque, torque)
|
||||
self.safety.set_toyota_desired_torque_last(torque - MAX_RATE_UP)
|
||||
|
||||
if controls_allowed:
|
||||
send = (-MAX_TORQUE <= torque <= MAX_TORQUE)
|
||||
|
@ -181,14 +181,14 @@ class TestToyotaSafety(unittest.TestCase):
|
|||
def test_non_realtime_limit_down(self):
|
||||
self.safety.set_controls_allowed(True)
|
||||
|
||||
self.safety.set_rt_torque_last(1000)
|
||||
self.safety.set_torque_meas(500, 500)
|
||||
self.safety.set_desired_torque_last(1000)
|
||||
self.safety.set_toyota_rt_torque_last(1000)
|
||||
self.safety.set_toyota_torque_meas(500, 500)
|
||||
self.safety.set_toyota_desired_torque_last(1000)
|
||||
self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(1000 - MAX_RATE_DOWN)))
|
||||
|
||||
self.safety.set_rt_torque_last(1000)
|
||||
self.safety.set_torque_meas(500, 500)
|
||||
self.safety.set_desired_torque_last(1000)
|
||||
self.safety.set_toyota_rt_torque_last(1000)
|
||||
self.safety.set_toyota_torque_meas(500, 500)
|
||||
self.safety.set_toyota_desired_torque_last(1000)
|
||||
self.assertFalse(self.safety.toyota_tx_hook(self._torque_msg(1000 - MAX_RATE_DOWN + 1)))
|
||||
|
||||
def test_exceed_torque_sensor(self):
|
||||
|
@ -210,14 +210,14 @@ class TestToyotaSafety(unittest.TestCase):
|
|||
self._set_prev_torque(0)
|
||||
for t in np.arange(0, 380, 10):
|
||||
t *= sign
|
||||
self.safety.set_torque_meas(t, t)
|
||||
self.safety.set_toyota_torque_meas(t, t)
|
||||
self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(t)))
|
||||
self.assertFalse(self.safety.toyota_tx_hook(self._torque_msg(sign * 380)))
|
||||
|
||||
self._set_prev_torque(0)
|
||||
for t in np.arange(0, 370, 10):
|
||||
t *= sign
|
||||
self.safety.set_torque_meas(t, t)
|
||||
self.safety.set_toyota_torque_meas(t, t)
|
||||
self.assertTrue(self.safety.toyota_tx_hook(self._torque_msg(t)))
|
||||
|
||||
# Increase timer to update rt_torque_last
|
||||
|
@ -233,16 +233,16 @@ class TestToyotaSafety(unittest.TestCase):
|
|||
self.safety.toyota_rx_hook(self._torque_meas_msg(0))
|
||||
self.safety.toyota_rx_hook(self._torque_meas_msg(0))
|
||||
|
||||
self.assertEqual(-51, self.safety.get_torque_meas_min())
|
||||
self.assertEqual(51, self.safety.get_torque_meas_max())
|
||||
self.assertEqual(-51, self.safety.get_toyota_torque_meas_min())
|
||||
self.assertEqual(51, self.safety.get_toyota_torque_meas_max())
|
||||
|
||||
self.safety.toyota_rx_hook(self._torque_meas_msg(0))
|
||||
self.assertEqual(-1, self.safety.get_torque_meas_max())
|
||||
self.assertEqual(-51, self.safety.get_torque_meas_min())
|
||||
self.assertEqual(-1, self.safety.get_toyota_torque_meas_max())
|
||||
self.assertEqual(-51, self.safety.get_toyota_torque_meas_min())
|
||||
|
||||
self.safety.toyota_rx_hook(self._torque_meas_msg(0))
|
||||
self.assertEqual(-1, self.safety.get_torque_meas_max())
|
||||
self.assertEqual(-1, self.safety.get_torque_meas_min())
|
||||
self.assertEqual(-1, self.safety.get_toyota_torque_meas_max())
|
||||
self.assertEqual(-1, self.safety.get_toyota_torque_meas_min())
|
||||
|
||||
def test_ipas_override(self):
|
||||
|
||||
|
|
Binary file not shown.
After Width: | Height: | Size: 24 KiB |
|
@ -1,6 +1,6 @@
|
|||
#!/usr/bin/env python
|
||||
from common.realtime import sec_since_boot
|
||||
from cereal import car
|
||||
from cereal import car, log
|
||||
from selfdrive.swaglog import cloudlog
|
||||
from selfdrive.config import Conversions as CV
|
||||
from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event
|
||||
|
@ -209,7 +209,7 @@ class CarInterface(object):
|
|||
|
||||
# pass in a car.CarControl
|
||||
# to be called @ 100hz
|
||||
def apply(self, c):
|
||||
def apply(self, c, perception_state=log.Live20Data.new_message()):
|
||||
|
||||
self.CC.update(self.sendcan, c.enabled, self.CS, self.frame, c.actuators,
|
||||
c.hudControl.visualAlert, c.cruiseControl.cancel)
|
||||
|
|
|
@ -4,7 +4,8 @@ from common.kalman.simple_kalman import KF1D
|
|||
from selfdrive.config import Conversions as CV
|
||||
from selfdrive.can.parser import CANParser
|
||||
from selfdrive.car.gm.values import DBC, CAR, parse_gear_shifter, \
|
||||
CruiseButtons, is_eps_status_ok
|
||||
CruiseButtons, is_eps_status_ok, \
|
||||
STEER_THRESHOLD
|
||||
|
||||
def get_powertrain_can_parser(CP, canbus):
|
||||
# this function generates lists for signal, messages and initial values
|
||||
|
@ -91,7 +92,7 @@ class CarState(object):
|
|||
self.user_gas_pressed = self.pedal_gas > 0
|
||||
|
||||
self.steer_torque_driver = pt_cp.vl["PSCMStatus"]['LKADriverAppldTrq']
|
||||
self.steer_override = abs(self.steer_torque_driver) > 1.0
|
||||
self.steer_override = abs(self.steer_torque_driver) > STEER_THRESHOLD
|
||||
|
||||
# 0 - inactive, 1 - active, 2 - temporary limited, 3 - failed
|
||||
self.lkas_status = pt_cp.vl["PSCMStatus"]['LKATorqueDeliveredStatus']
|
||||
|
|
|
@ -1,5 +1,5 @@
|
|||
#!/usr/bin/env python
|
||||
from cereal import car
|
||||
from cereal import car, log
|
||||
from common.realtime import sec_since_boot
|
||||
from selfdrive.config import Conversions as CV
|
||||
from selfdrive.controls.lib.drive_helpers import create_event, EventTypes as ET
|
||||
|
@ -308,7 +308,7 @@ class CarInterface(object):
|
|||
|
||||
# pass in a car.CarControl
|
||||
# to be called @ 100hz
|
||||
def apply(self, c):
|
||||
def apply(self, c, perception_state=log.Live20Data.new_message()):
|
||||
hud_v_cruise = c.hudControl.setSpeed
|
||||
if hud_v_cruise > 70:
|
||||
hud_v_cruise = 0
|
||||
|
|
|
@ -47,6 +47,7 @@ FINGERPRINTS = {
|
|||
}],
|
||||
}
|
||||
|
||||
STEER_THRESHOLD = 1.0
|
||||
|
||||
DBC = {
|
||||
CAR.VOLT: dbc_dict('gm_global_a_powertrain', 'gm_global_a_object', chassis_dbc='gm_global_a_chassis'),
|
||||
|
|
|
@ -1,3 +1,4 @@
|
|||
from cereal import car
|
||||
from collections import namedtuple
|
||||
from selfdrive.boardd.boardd import can_list_to_can_capnp
|
||||
from selfdrive.controls.lib.drive_helpers import rate_limit
|
||||
|
@ -61,11 +62,12 @@ class CarController(object):
|
|||
self.brake_last = 0.
|
||||
self.enable_camera = enable_camera
|
||||
self.packer = CANPacker(dbc_name)
|
||||
self.new_radar_config = False
|
||||
|
||||
def update(self, sendcan, enabled, CS, frame, actuators, \
|
||||
pcm_speed, pcm_override, pcm_cancel_cmd, pcm_accel, \
|
||||
hud_v_cruise, hud_show_lanes, hud_show_car, hud_alert, \
|
||||
snd_beep, snd_chime):
|
||||
radar_error, hud_v_cruise, hud_show_lanes, hud_show_car, \
|
||||
hud_alert, snd_beep, snd_chime):
|
||||
|
||||
""" Controls thread """
|
||||
|
||||
|
@ -167,6 +169,8 @@ class CarController(object):
|
|||
|
||||
if (frame % radar_send_step) == 0:
|
||||
idx = (frame/radar_send_step) % 4
|
||||
can_sends.extend(hondacan.create_radar_commands(CS.v_ego, CS.CP.carFingerprint, idx))
|
||||
if not self.new_radar_config: # only change state once
|
||||
self.new_radar_config = car.RadarState.Error.wrongConfig in radar_error
|
||||
can_sends.extend(hondacan.create_radar_commands(CS.v_ego, CS.CP.carFingerprint, self.new_radar_config, idx))
|
||||
|
||||
sendcan.send(can_list_to_can_capnp(can_sends, msgtype='sendcan').to_bytes())
|
||||
|
|
|
@ -2,7 +2,7 @@ from common.numpy_fast import interp
|
|||
from common.kalman.simple_kalman import KF1D
|
||||
from selfdrive.can.parser import CANParser
|
||||
from selfdrive.config import Conversions as CV
|
||||
from selfdrive.car.honda.values import CAR, DBC
|
||||
from selfdrive.car.honda.values import CAR, DBC, STEER_THRESHOLD
|
||||
|
||||
def parse_gear_shifter(can_gear_shifter, car_fingerprint):
|
||||
|
||||
|
@ -284,10 +284,8 @@ class CarState(object):
|
|||
else:
|
||||
self.car_gas = cp.vl["GAS_PEDAL_2"]['CAR_GAS']
|
||||
|
||||
#rdx has different steer override threshold
|
||||
steer_thrsld = 400 if self.CP.carFingerprint == CAR.ACURA_RDX else 1200
|
||||
self.steer_override = abs(cp.vl["STEER_STATUS"]['STEER_TORQUE_SENSOR']) > steer_thrsld
|
||||
self.steer_torque_driver = cp.vl["STEER_STATUS"]['STEER_TORQUE_SENSOR']
|
||||
self.steer_override = abs(self.steer_torque_driver) > STEER_THRESHOLD[self.CP.carFingerprint]
|
||||
|
||||
self.brake_switch = cp.vl["POWERTRAIN_DATA"]['BRAKE_SWITCH']
|
||||
|
||||
|
|
|
@ -117,7 +117,7 @@ def create_ui_commands(packer, pcm_speed, hud, car_fingerprint, idx):
|
|||
return commands
|
||||
|
||||
|
||||
def create_radar_commands(v_ego, car_fingerprint, idx):
|
||||
def create_radar_commands(v_ego, car_fingerprint, new_radar_config, idx):
|
||||
"""Creates an iterable of CAN messages for the radar system."""
|
||||
commands = []
|
||||
v_ego_kph = np.clip(int(round(v_ego * CV.MS_TO_KPH)), 0, 255)
|
||||
|
@ -129,7 +129,8 @@ def create_radar_commands(v_ego, car_fingerprint, idx):
|
|||
|
||||
if car_fingerprint == CAR.CIVIC:
|
||||
msg_0x301 = "\x02\x38\x44\x32\x4f\x00\x00"
|
||||
commands.append(make_can_msg(0x300, msg_0x300, idx + 8, 1)) # add 8 on idx.
|
||||
idx_offset = 0xc if new_radar_config else 0x8 # radar in civic 2018 requires 0xc
|
||||
commands.append(make_can_msg(0x300, msg_0x300, idx + idx_offset, 1))
|
||||
else:
|
||||
if car_fingerprint == CAR.CRV:
|
||||
msg_0x301 = "\x00\x00\x50\x02\x51\x00\x00"
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
#!/usr/bin/env python
|
||||
import os
|
||||
import numpy as np
|
||||
from cereal import car
|
||||
from cereal import car, log
|
||||
from common.numpy_fast import clip, interp
|
||||
from common.realtime import sec_since_boot
|
||||
from selfdrive.swaglog import cloudlog
|
||||
|
@ -567,7 +567,7 @@ class CarInterface(object):
|
|||
|
||||
# pass in a car.CarControl
|
||||
# to be called @ 100hz
|
||||
def apply(self, c):
|
||||
def apply(self, c, perception_state=log.Live20Data.new_message()):
|
||||
if c.hudControl.speedVisible:
|
||||
hud_v_cruise = c.hudControl.setSpeed * CV.MS_TO_KPH
|
||||
else:
|
||||
|
@ -600,6 +600,7 @@ class CarInterface(object):
|
|||
c.cruiseControl.override, \
|
||||
c.cruiseControl.cancel, \
|
||||
pcm_accel, \
|
||||
perception_state.radarErrors, \
|
||||
hud_v_cruise, c.hudControl.lanesVisible, \
|
||||
hud_show_car = c.hudControl.leadVisible, \
|
||||
hud_alert = hud_alert, \
|
||||
|
|
|
@ -28,6 +28,7 @@ class RadarInterface(object):
|
|||
self.pts = {}
|
||||
self.track_id = 0
|
||||
self.radar_fault = False
|
||||
self.radar_wrong_config = False
|
||||
self.radar_off_can = CP.radarOffCan
|
||||
|
||||
self.delay = 0.1 # Delay of radar
|
||||
|
@ -61,6 +62,7 @@ class RadarInterface(object):
|
|||
if ii == 0x400:
|
||||
# check for radar faults
|
||||
self.radar_fault = cpt['RADAR_STATE'] != 0x79
|
||||
self.radar_wrong_config = cpt['RADAR_STATE'] == 0x69
|
||||
elif cpt['LONG_DIST'] < 255:
|
||||
if ii not in self.pts or cpt['NEW_TRACK']:
|
||||
self.pts[ii] = car.RadarState.RadarPoint.new_message()
|
||||
|
@ -81,6 +83,8 @@ class RadarInterface(object):
|
|||
errors.append("commIssue")
|
||||
if self.radar_fault:
|
||||
errors.append("fault")
|
||||
if self.radar_wrong_config:
|
||||
errors.append("wrongConfig")
|
||||
ret.errors = errors
|
||||
ret.canMonoTimes = canMonoTimes
|
||||
|
||||
|
|
|
@ -104,5 +104,19 @@ DBC = {
|
|||
CAR.RIDGELINE: dbc_dict('honda_ridgeline_black_edition_2017_can_generated', 'acura_ilx_2016_nidec'),
|
||||
}
|
||||
|
||||
|
||||
STEER_THRESHOLD = {
|
||||
CAR.ACCORD: 1200,
|
||||
CAR.ACURA_ILX: 1200,
|
||||
CAR.ACURA_RDX: 400,
|
||||
CAR.CIVIC: 1200,
|
||||
CAR.CIVIC_HATCH: 1200,
|
||||
CAR.CRV: 1200,
|
||||
CAR.CRV_5G: 1200,
|
||||
CAR.ODYSSEY: 1200,
|
||||
CAR.PILOT: 1200,
|
||||
CAR.RIDGELINE: 1200,
|
||||
}
|
||||
|
||||
# TODO: get these from dbc file
|
||||
HONDA_BOSCH = [CAR.ACCORD, CAR.CIVIC_HATCH, CAR.CRV_5G]
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/usr/bin/env python
|
||||
import zmq
|
||||
from cereal import car
|
||||
from cereal import car, log
|
||||
from selfdrive.config import Conversions as CV
|
||||
from selfdrive.services import service_list
|
||||
from selfdrive.swaglog import cloudlog
|
||||
|
@ -117,6 +117,6 @@ class CarInterface(object):
|
|||
|
||||
return ret.as_reader()
|
||||
|
||||
def apply(self, c):
|
||||
def apply(self, c, perception_state=log.Live20Data.new_message()):
|
||||
# in mock no carcontrols
|
||||
return False
|
||||
|
|
|
@ -4,7 +4,7 @@ from selfdrive.car.toyota.toyotacan import make_can_msg, create_video_target,\
|
|||
create_steer_command, create_ui_command, \
|
||||
create_ipas_steer_command, create_accel_command, \
|
||||
create_fcw_command
|
||||
from selfdrive.car.toyota.values import ECU, STATIC_MSGS
|
||||
from selfdrive.car.toyota.values import ECU, STATIC_MSGS, NO_DSU_CAR
|
||||
from selfdrive.can.packer import CANPacker
|
||||
|
||||
# Accel limits
|
||||
|
@ -209,7 +209,7 @@ class CarController(object):
|
|||
else:
|
||||
can_sends.append(create_accel_command(self.packer, 0, pcm_cancel_cmd, False))
|
||||
|
||||
if frame % 10 == 0 and ECU.CAM in self.fake_ecus:
|
||||
if frame % 10 == 0 and ECU.CAM in self.fake_ecus and self.car_fingerprint not in NO_DSU_CAR:
|
||||
for addr in TARGET_IDS:
|
||||
can_sends.append(create_video_target(frame/10, addr))
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
from selfdrive.car.toyota.values import CAR, DBC
|
||||
from selfdrive.car.toyota.values import CAR, DBC, STEER_THRESHOLD
|
||||
from selfdrive.can.parser import CANParser
|
||||
from selfdrive.config import Conversions as CV
|
||||
from common.kalman.simple_kalman import KF1D
|
||||
|
@ -7,7 +7,7 @@ import numpy as np
|
|||
|
||||
def parse_gear_shifter(can_gear, car_fingerprint):
|
||||
# TODO: Use values from DBC to parse this field
|
||||
if car_fingerprint == CAR.PRIUS:
|
||||
if car_fingerprint in [CAR.PRIUS, CAR.CHRH, CAR.CAMRYH]:
|
||||
if can_gear == 0x0:
|
||||
return "park"
|
||||
elif can_gear == 0x1:
|
||||
|
@ -19,7 +19,7 @@ def parse_gear_shifter(can_gear, car_fingerprint):
|
|||
elif can_gear == 0x4:
|
||||
return "brake"
|
||||
elif car_fingerprint in [CAR.RAV4, CAR.RAV4H,
|
||||
CAR.LEXUS_RXH, CAR.COROLLA]:
|
||||
CAR.LEXUS_RXH, CAR.COROLLA, CAR.CHR, CAR.CAMRY]:
|
||||
if can_gear == 0x20:
|
||||
return "park"
|
||||
elif can_gear == 0x10:
|
||||
|
@ -147,8 +147,6 @@ class CarState(object):
|
|||
self.left_blinker_on = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 1
|
||||
self.right_blinker_on = cp.vl["STEERING_LEVERS"]['TURN_SIGNALS'] == 2
|
||||
|
||||
# we could use the override bit from dbc, but it's triggered at too high torque values
|
||||
self.steer_override = abs(cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_DRIVER']) > 100
|
||||
# 2 is standby, 10 is active. TODO: check that everything else is really a faulty state
|
||||
self.steer_state = cp.vl["EPS_STATUS"]['LKA_STATE']
|
||||
self.steer_error = cp.vl["EPS_STATUS"]['LKA_STATE'] not in [1, 5]
|
||||
|
@ -156,6 +154,8 @@ class CarState(object):
|
|||
self.brake_error = 0
|
||||
self.steer_torque_driver = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_DRIVER']
|
||||
self.steer_torque_motor = cp.vl["STEER_TORQUE_SENSOR"]['STEER_TORQUE_EPS']
|
||||
# we could use the override bit from dbc, but it's triggered at too high torque values
|
||||
self.steer_override = abs(self.steer_torque_driver) > STEER_THRESHOLD
|
||||
|
||||
self.user_brake = 0
|
||||
self.v_cruise_pcm = cp.vl["PCM_CRUISE_2"]['SET_SPEED']
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
#!/usr/bin/env python
|
||||
from common.realtime import sec_since_boot
|
||||
from cereal import car
|
||||
from cereal import car, log
|
||||
from selfdrive.config import Conversions as CV
|
||||
from selfdrive.controls.lib.drive_helpers import EventTypes as ET, create_event
|
||||
from selfdrive.controls.lib.vehicle_model import VehicleModel
|
||||
|
@ -75,8 +75,8 @@ class CarInterface(object):
|
|||
if candidate == CAR.PRIUS:
|
||||
ret.safetyParam = 66 # see conversion factor for STEER_TORQUE_EPS in dbc file
|
||||
ret.wheelbase = 2.70
|
||||
ret.steerRatio = 15.59 # unknown end-to-end spec
|
||||
tire_stiffness_factor = 0.7933
|
||||
ret.steerRatio = 15.00 # unknown end-to-end spec
|
||||
tire_stiffness_factor = 0.6371 # hand-tune
|
||||
ret.mass = 3045 * CV.LB_TO_KG + std_cargo
|
||||
ret.steerKpV, ret.steerKiV = [[0.4], [0.01]]
|
||||
ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594
|
||||
|
@ -110,6 +110,24 @@ class CarInterface(object):
|
|||
ret.steerKpV, ret.steerKiV = [[0.6], [0.1]]
|
||||
ret.steerKf = 0.00006 # full torque for 10 deg at 80mph means 0.00007818594
|
||||
|
||||
elif candidate in [CAR.CHR, CAR.CHRH]:
|
||||
ret.safetyParam = 100
|
||||
ret.wheelbase = 2.63906
|
||||
ret.steerRatio = 13.6
|
||||
tire_stiffness_factor = 0.7933
|
||||
ret.mass = 3300. * CV.LB_TO_KG + std_cargo
|
||||
ret.steerKpV, ret.steerKiV = [[0.723], [0.0428]]
|
||||
ret.steerKf = 0.00006
|
||||
|
||||
elif candidate in [CAR.CAMRY, CAR.CAMRYH]:
|
||||
ret.safetyParam = 100
|
||||
ret.wheelbase = 2.82448
|
||||
ret.steerRatio = 13.7
|
||||
tire_stiffness_factor = 0.7933
|
||||
ret.mass = 3400 * CV.LB_TO_KG + std_cargo #mean between normal and hybrid
|
||||
ret.steerKpV, ret.steerKiV = [[0.6], [0.1]]
|
||||
ret.steerKf = 0.00006
|
||||
|
||||
ret.steerRateCost = 1.
|
||||
ret.centerToFront = ret.wheelbase * 0.44
|
||||
|
||||
|
@ -118,7 +136,7 @@ class CarInterface(object):
|
|||
|
||||
# min speed to enable ACC. if car can do stop and go, then set enabling speed
|
||||
# to a negative value, so it won't matter.
|
||||
if candidate in [CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH]: # rav4 hybrid can do stop and go
|
||||
if candidate in [CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH]: # rav4 hybrid can do stop and go
|
||||
ret.minEnableSpeed = -1.
|
||||
elif candidate in [CAR.RAV4, CAR.COROLLA]: # TODO: hack ICE to do stop and go
|
||||
ret.minEnableSpeed = 19. * CV.MPH_TO_MS
|
||||
|
@ -150,9 +168,9 @@ class CarInterface(object):
|
|||
ret.brakeMaxBP = [5., 20.]
|
||||
ret.brakeMaxV = [1., 0.8]
|
||||
|
||||
ret.enableCamera = not check_ecu_msgs(fingerprint, candidate, ECU.CAM)
|
||||
ret.enableDsu = not check_ecu_msgs(fingerprint, candidate, ECU.DSU)
|
||||
ret.enableApgs = False #not check_ecu_msgs(fingerprint, candidate, ECU.APGS)
|
||||
ret.enableCamera = not check_ecu_msgs(fingerprint, ECU.CAM)
|
||||
ret.enableDsu = not check_ecu_msgs(fingerprint, ECU.DSU)
|
||||
ret.enableApgs = False #not check_ecu_msgs(fingerprint, ECU.APGS)
|
||||
cloudlog.warn("ECU Camera Simulated: %r", ret.enableCamera)
|
||||
cloudlog.warn("ECU DSU Simulated: %r", ret.enableDsu)
|
||||
cloudlog.warn("ECU APGS Simulated: %r", ret.enableApgs)
|
||||
|
@ -304,7 +322,7 @@ class CarInterface(object):
|
|||
|
||||
# pass in a car.CarControl
|
||||
# to be called @ 100hz
|
||||
def apply(self, c):
|
||||
def apply(self, c, perception_state=log.Live20Data.new_message()):
|
||||
|
||||
self.CC.update(self.sendcan, c.enabled, self.CS, self.frame,
|
||||
c.actuators, c.cruiseControl.cancel, c.hudControl.visualAlert,
|
||||
|
|
|
@ -1,11 +1,13 @@
|
|||
#!/usr/bin/env python
|
||||
import os
|
||||
import zmq
|
||||
import time
|
||||
from selfdrive.can.parser import CANParser
|
||||
from cereal import car
|
||||
from common.realtime import sec_since_boot
|
||||
import zmq
|
||||
from selfdrive.services import service_list
|
||||
import selfdrive.messaging as messaging
|
||||
from selfdrive.car.toyota.values import NO_DSU_CAR
|
||||
|
||||
|
||||
RADAR_MSGS = list(range(0x210, 0x220))
|
||||
|
@ -30,15 +32,21 @@ class RadarInterface(object):
|
|||
|
||||
self.delay = 0.0 # Delay of radar
|
||||
|
||||
# Nidec
|
||||
self.rcp = _create_radard_can_parser()
|
||||
self.no_dsu_car = CP.carFingerprint in NO_DSU_CAR
|
||||
|
||||
context = zmq.Context()
|
||||
self.logcan = messaging.sub_sock(context, service_list['can'].port)
|
||||
|
||||
def update(self):
|
||||
canMonoTimes = []
|
||||
|
||||
ret = car.RadarState.new_message()
|
||||
if self.no_dsu_car:
|
||||
# TODO: make a adas dbc file for dsu-less models
|
||||
time.sleep(0.05)
|
||||
return ret
|
||||
|
||||
canMonoTimes = []
|
||||
updated_messages = set()
|
||||
while 1:
|
||||
tm = int(sec_since_boot() * 1e9)
|
||||
|
@ -47,7 +55,6 @@ class RadarInterface(object):
|
|||
if 0x21f in updated_messages:
|
||||
break
|
||||
|
||||
ret = car.RadarState.new_message()
|
||||
errors = []
|
||||
if not self.rcp.can_valid:
|
||||
errors.append("commIssue")
|
||||
|
|
|
@ -2,10 +2,14 @@ from selfdrive.car import dbc_dict
|
|||
|
||||
class CAR:
|
||||
PRIUS = "TOYOTA PRIUS 2017"
|
||||
RAV4H = "TOYOTA RAV4 2017 HYBRID"
|
||||
RAV4H = "TOYOTA RAV4 HYBRID 2017"
|
||||
RAV4 = "TOYOTA RAV4 2017"
|
||||
COROLLA = "TOYOTA COROLLA 2017"
|
||||
LEXUS_RXH = "LEXUS RX HYBRID 2017"
|
||||
CHR = "TOYOTA C-HR 2018"
|
||||
CHRH = "TOYOTA C-HR HYBRID 2018"
|
||||
CAMRY = "TOYOTA CAMRY 2018"
|
||||
CAMRYH = "TOYOTA CAMRY HYBRID 2018"
|
||||
|
||||
|
||||
class ECU:
|
||||
|
@ -59,14 +63,16 @@ STATIC_MSGS = [(0x141, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH, CAR.RAV4,
|
|||
(0x470, ECU.DSU, (CAR.PRIUS, CAR.RAV4H, CAR.LEXUS_RXH), 1, 100, '\x00\x00\x02\x7a'),
|
||||
]
|
||||
|
||||
ECU_FINGERPRINT = {
|
||||
ECU.CAM: 0x2e4, # steer torque cmd
|
||||
ECU.DSU: 0x343, # accel cmd
|
||||
ECU.APGS: 0x835, # angle cmd
|
||||
}
|
||||
|
||||
def check_ecu_msgs(fingerprint, candidate, ecu):
|
||||
|
||||
def check_ecu_msgs(fingerprint, ecu):
|
||||
# return True if fingerprint contains messages normally sent by a given ecu
|
||||
ecu_msgs = [x[0] for x in STATIC_MSGS if (x[1] == ecu and
|
||||
candidate in x[2] and
|
||||
x[3] == 0)]
|
||||
|
||||
return any(msg for msg in fingerprint if msg in ecu_msgs)
|
||||
return ECU_FINGERPRINT[ecu] in fingerprint
|
||||
|
||||
|
||||
FINGERPRINTS = {
|
||||
|
@ -97,8 +103,25 @@ FINGERPRINTS = {
|
|||
CAR.LEXUS_RXH: [{
|
||||
36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 5, 643: 7, 658: 8, 713: 8, 740: 5, 742: 8, 743: 8, 800: 8, 810: 2, 812: 3, 814: 8, 830: 7, 835: 8, 836: 8, 845: 5, 863: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 918: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 6, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1005: 2, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1063: 8, 1071: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1227: 8, 1228: 8, 1235: 8, 1237: 8, 1264: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1575: 8, 1595: 8, 1777: 8, 1779: 8, 1808: 8, 1810: 8, 1816: 8, 1818: 8, 1840: 8, 1848: 8, 1904: 8, 1912: 8, 1940: 8, 1941: 8, 1948: 8, 1949: 8, 1952: 8, 1956: 8, 1960: 8, 1964: 8, 1986: 8, 1990: 8, 1994: 8, 1998: 8, 2004: 8, 2012: 8
|
||||
}],
|
||||
CAR.CHR: [{
|
||||
36: 8, 37: 8, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 705: 8, 740: 5, 800: 8, 810: 2, 812: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 921: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1235: 8, 1279: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8
|
||||
}],
|
||||
CAR.CHRH: [{
|
||||
36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 740: 5, 800: 8, 810: 2, 812: 8, 829: 2, 830: 7, 835: 8, 836: 8, 845: 5, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 913: 8, 921: 8, 933: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1014: 8, 1017: 8, 1020: 8, 1021: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8,1059: 1, 1071: 8, 1076: 8, 1077: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1235: 8, 1237: 8, 1279: 8, 1552: 8, 1553: 8, 1556:8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
|
||||
}],
|
||||
CAR.CAMRY: [
|
||||
#XLE and LE
|
||||
{
|
||||
36: 8, 37: 8, 119: 6, 170: 8, 180: 8, 186: 4, 426: 6, 452: 8, 464: 8, 466: 8, 467: 8, 544: 4, 550: 8, 552: 4, 562: 6, 608: 8, 610: 8, 643: 7, 658: 8, 705: 8, 728: 8, 740: 5, 761: 8, 764: 8, 800: 8, 810: 2, 812: 8, 814: 8, 818: 8, 822: 8, 824: 8, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 888: 8, 889: 8, 891: 8, 898: 8, 900: 6, 902: 6, 905: 8, 918: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 951: 8, 955: 8, 956: 8, 976: 1, 983: 8, 984: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1011: 8, 1014: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1059: 1, 1076: 8, 1077: 8, 1082: 8, 1114: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1228: 8, 1235: 8, 1237: 8, 1263: 8, 1264: 8, 1279: 8, 1412: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572: 8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1808: 8, 1816: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
|
||||
}],
|
||||
CAR.CAMRYH: [
|
||||
#LE
|
||||
{
|
||||
36: 8, 37: 8, 166: 8, 170: 8, 180: 8, 295: 8, 296: 8, 426: 6, 452: 8, 466: 8, 467: 8, 550: 8, 552: 4, 560: 7, 562: 6, 581: 5, 608: 8, 610: 8, 643: 7, 713: 8, 728: 8, 740: 5, 761: 8, 764: 8, 800: 8, 810: 2, 812: 8, 824: 8, 829: 2, 830: 7, 835: 8, 836: 8, 869: 7, 870: 7, 871: 2, 898: 8, 900: 6, 902: 6, 905: 8, 921: 8, 933: 8, 934: 8, 935: 8, 944: 8, 945: 8, 950: 8, 951: 8, 953: 8, 955: 8, 956: 8, 971: 7, 975: 5, 993: 8, 998: 5, 999: 7, 1000: 8, 1001: 8, 1002: 8, 1017: 8, 1020: 8, 1041: 8, 1042: 8, 1044: 8, 1056: 8, 1057: 8, 1059: 1, 1071: 8, 1076: 8, 1077: 8, 1084: 8, 1085: 8, 1086: 8, 1114: 8, 1132: 8, 1161: 8, 1162: 8, 1163: 8, 1164: 8, 1165: 8, 1166: 8, 1167: 8, 1235: 8, 1279: 8, 1541: 8, 1552: 8, 1553: 8, 1556: 8, 1557: 8, 1568: 8, 1570: 8, 1571: 8, 1572:8, 1595: 8, 1745: 8, 1779: 8, 1786: 8, 1787: 8, 1788: 8, 1789: 8, 1904: 8, 1912: 8, 1990: 8, 1998: 8
|
||||
}],
|
||||
}
|
||||
|
||||
STEER_THRESHOLD = 100
|
||||
|
||||
DBC = {
|
||||
CAR.RAV4H: dbc_dict('toyota_rav4_hybrid_2017_pt_generated', 'toyota_prius_2017_adas'),
|
||||
|
@ -106,4 +129,10 @@ DBC = {
|
|||
CAR.PRIUS: dbc_dict('toyota_prius_2017_pt_generated', 'toyota_prius_2017_adas'),
|
||||
CAR.COROLLA: dbc_dict('toyota_corolla_2017_pt_generated', 'toyota_prius_2017_adas'),
|
||||
CAR.LEXUS_RXH: dbc_dict('lexus_rx_hybrid_2017_pt_generated', 'toyota_prius_2017_adas'),
|
||||
CAR.CHR: dbc_dict('toyota_chr_2018_pt_generated', 'toyota_prius_2017_adas'),
|
||||
CAR.CHRH: dbc_dict('toyota_chr_hybrid_2018_pt_generated', 'toyota_prius_2017_adas'),
|
||||
CAR.CAMRY: dbc_dict('toyota_chr_2018_pt_generated', 'toyota_prius_2017_adas'),
|
||||
CAR.CAMRYH: dbc_dict('toyota_camry_hybrid_2018_pt_generated', 'toyota_prius_2017_adas'),
|
||||
}
|
||||
|
||||
NO_DSU_CAR = [CAR.CHR, CAR.CHRH, CAR.CAMRY, CAR.CAMRYH]
|
||||
|
|
|
@ -0,0 +1,56 @@
|
|||
#include <stdlib.h>
|
||||
#include <assert.h>
|
||||
|
||||
#ifdef __linux__
|
||||
#include <sys/eventfd.h>
|
||||
#else
|
||||
#include <sys/time.h>
|
||||
#include <sys/event.h>
|
||||
#define EVENT_IDENT 42
|
||||
#endif
|
||||
|
||||
#include "efd.h"
|
||||
|
||||
|
||||
int efd_init() {
|
||||
#ifdef __linux__
|
||||
return eventfd(0, EFD_CLOEXEC);
|
||||
#else
|
||||
int fd = kqueue();
|
||||
assert(fd >= 0);
|
||||
|
||||
struct kevent kev;
|
||||
EV_SET(&kev, EVENT_IDENT, EVFILT_USER, EV_ADD | EV_CLEAR, 0, 0, NULL);
|
||||
|
||||
struct timespec timeout = {0, 0};
|
||||
int err = kevent(fd, &kev, 1, NULL, 0, &timeout);
|
||||
assert(err != -1);
|
||||
|
||||
return fd;
|
||||
#endif
|
||||
}
|
||||
|
||||
void efd_write(int fd) {
|
||||
#ifdef __linux__
|
||||
eventfd_write(fd, 1);
|
||||
#else
|
||||
struct kevent kev;
|
||||
EV_SET(&kev, EVENT_IDENT, EVFILT_USER, 0, NOTE_TRIGGER, 0, NULL);
|
||||
|
||||
struct timespec timeout = {0, 0};
|
||||
int err = kevent(fd, &kev, 1, NULL, 0, &timeout);
|
||||
assert(err != -1);
|
||||
#endif
|
||||
}
|
||||
|
||||
void efd_clear(int fd) {
|
||||
#ifdef __linux__
|
||||
eventfd_t efd_cnt;
|
||||
eventfd_read(fd, &efd_cnt);
|
||||
#else
|
||||
struct kevent kev;
|
||||
struct timespec timeout = {0, 0};
|
||||
int nfds = kevent(fd, NULL, 0, &kev, 1, &timeout);
|
||||
assert(nfds != -1);
|
||||
#endif
|
||||
}
|
|
@ -0,0 +1,17 @@
|
|||
#ifndef EFD_H
|
||||
#define EFD_H
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C" {
|
||||
#endif
|
||||
|
||||
// event fd: a semaphore that can be poll()'d
|
||||
int efd_init();
|
||||
void efd_write(int fd);
|
||||
void efd_clear(int fd);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif
|
|
@ -1 +1 @@
|
|||
#define COMMA_VERSION "0.5-release"
|
||||
#define COMMA_VERSION "0.5.1-release"
|
||||
|
|
|
@ -292,7 +292,7 @@ def state_control(plan, CS, CP, state, events, v_cruise_kph, v_cruise_kph_last,
|
|||
return actuators, v_cruise_kph, driver_status, angle_offset
|
||||
|
||||
|
||||
def data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate,
|
||||
def data_send(perception_state, plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate,
|
||||
carcontrol, live100, livempc, AM, driver_status,
|
||||
LaC, LoC, angle_offset, passive):
|
||||
|
||||
|
@ -323,7 +323,7 @@ def data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_
|
|||
CC.hudControl.audibleAlert = AM.audible_alert
|
||||
|
||||
# send car controls over can
|
||||
CI.apply(CC)
|
||||
CI.apply(CC, perception_state)
|
||||
|
||||
# ***** publish state to logger *****
|
||||
# publish controls state at 100Hz
|
||||
|
@ -337,6 +337,7 @@ def data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_
|
|||
"alertStatus": AM.alert_status,
|
||||
"alertBlinkingRate": AM.alert_rate,
|
||||
"awarenessStatus": max(driver_status.awareness, 0.0) if isEnabled(state) else 0.0,
|
||||
"driverMonitoringOn": bool(driver_status.monitor_on),
|
||||
"canMonoTimes": list(CS.canMonoTimes),
|
||||
"planMonoTime": plan_ts,
|
||||
"enabled": isEnabled(state),
|
||||
|
@ -446,7 +447,6 @@ def controlsd_thread(gctx=None, rate=100, default_bias=0.):
|
|||
CP.safetyModel = car.CarParams.SafetyModels.noOutput
|
||||
|
||||
fcw_enabled = params.get("IsFcwEnabled") == "1"
|
||||
driver_monitor_on = params.get("IsDriverMonitoringEnabled") == "1"
|
||||
geofence = None
|
||||
try:
|
||||
from selfdrive.controls.lib.geofence import Geofence
|
||||
|
@ -460,7 +460,7 @@ def controlsd_thread(gctx=None, rate=100, default_bias=0.):
|
|||
VM = VehicleModel(CP)
|
||||
LaC = LatControl(VM)
|
||||
AM = AlertManager()
|
||||
driver_status = DriverStatus(driver_monitor_on)
|
||||
driver_status = DriverStatus()
|
||||
|
||||
if not passive:
|
||||
AM.add("startup", False)
|
||||
|
@ -516,7 +516,7 @@ def controlsd_thread(gctx=None, rate=100, default_bias=0.):
|
|||
prof.checkpoint("State Control")
|
||||
|
||||
# publish data
|
||||
CC = data_send(plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol,
|
||||
CC = data_send(PL.perception_state, plan, plan_ts, CS, CI, CP, VM, state, events, actuators, v_cruise_kph, rk, carstate, carcontrol,
|
||||
live100, livempc, AM, driver_status, LaC, LoC, angle_offset, passive)
|
||||
prof.checkpoint("Sent")
|
||||
|
||||
|
|
|
@ -74,7 +74,7 @@ class AlertManager(object):
|
|||
Priority.MID, None, "beepSingle", .2, 0., 0.),
|
||||
|
||||
"fcw": Alert(
|
||||
"Brake!",
|
||||
"BRAKE!",
|
||||
"Risk of Collision",
|
||||
AlertStatus.critical, AlertSize.full,
|
||||
Priority.HIGHEST, "fcw", "chimeRepeated", 1., 2., 2.),
|
||||
|
@ -98,23 +98,53 @@ class AlertManager(object):
|
|||
Priority.LOW, None, None, .2, .2, .2),
|
||||
|
||||
"preDriverDistracted": Alert(
|
||||
"TAKE CONTROL: User Appears Distracted",
|
||||
"KEEP EYES ON ROAD: User Appears Distracted",
|
||||
"",
|
||||
AlertStatus.normal, AlertSize.small,
|
||||
Priority.LOW, "steerRequired", None, 0., .1, .1, alert_rate=0.75),
|
||||
|
||||
"promptDriverDistracted": Alert(
|
||||
"TAKE CONTROL",
|
||||
"KEEP EYES ON ROAD",
|
||||
"User Appears Distracted",
|
||||
AlertStatus.userPrompt, AlertSize.mid,
|
||||
Priority.MID, "steerRequired", "chimeRepeated", .1, .1, .1),
|
||||
|
||||
"driverDistracted": Alert(
|
||||
"DISENGAGEMENT REQUIRED",
|
||||
"DISENGAGE IMMEDIATELY",
|
||||
"User Was Distracted",
|
||||
AlertStatus.critical, AlertSize.full,
|
||||
Priority.HIGH, "steerRequired", "chimeRepeated", .1, .1, .1),
|
||||
|
||||
"preDriverUnresponsive": Alert(
|
||||
"TOUCH STEERING WHEEL: No Driver Monitoring",
|
||||
"",
|
||||
AlertStatus.normal, AlertSize.small,
|
||||
Priority.LOW, "steerRequired", None, 0., .1, .1, alert_rate=0.75),
|
||||
|
||||
"promptDriverUnresponsive": Alert(
|
||||
"TOUCH STEERING WHEEL",
|
||||
"User Is Unresponsive",
|
||||
AlertStatus.userPrompt, AlertSize.mid,
|
||||
Priority.MID, "steerRequired", "chimeRepeated", .1, .1, .1),
|
||||
|
||||
"driverUnresponsive": Alert(
|
||||
"DISENGAGE IMMEDIATELY",
|
||||
"User Was Unresponsive",
|
||||
AlertStatus.critical, AlertSize.full,
|
||||
Priority.HIGH, "steerRequired", "chimeRepeated", .1, .1, .1),
|
||||
|
||||
"driverMonitorOff": Alert(
|
||||
"DRIVER MONITOR IS UNAVAILABLE",
|
||||
"Accuracy Is Low",
|
||||
AlertStatus.normal, AlertSize.mid,
|
||||
Priority.LOW, None, None, .4, 0., 4.),
|
||||
|
||||
"driverMonitorOn": Alert(
|
||||
"DRIVER MONITOR IS AVAILABLE",
|
||||
"Accuracy Is High",
|
||||
AlertStatus.normal, AlertSize.mid,
|
||||
Priority.LOW, None, None, .4, 0., 4.),
|
||||
|
||||
"geofence": Alert(
|
||||
"DISENGAGEMENT REQUIRED",
|
||||
"Not in Geofenced Area",
|
||||
|
|
|
@ -18,12 +18,22 @@ _CAMERA_X_CONV = 0.375 # 160*864/320/1152
|
|||
_PITCH_WEIGHT = 1.5 # pitch matters a lot more
|
||||
_METRIC_THRESHOLD = 0.4
|
||||
_PITCH_POS_ALLOWANCE = 0.08 # rad, to not be too sensitive on positive pitch
|
||||
_DTM = 0.2 # driver monitor runs at 5Hz
|
||||
_DISTRACTED_FILTER_F = 0.3 # 0.3Hz
|
||||
_DISTRACTED_FILTER_K = 2 * np.pi * _DISTRACTED_FILTER_F * _DTM / (1 + 2 * np.pi * _DISTRACTED_FILTER_F * _DTM)
|
||||
_DTM = 0.1 # driver monitor runs at 10Hz
|
||||
_PITCH_NATURAL_OFFSET = 0.1 # people don't seem to look straight when they drive relaxed, rather a bit up
|
||||
_STD_THRESHOLD = 0.1 # above this standard deviation consider the measurement invalid
|
||||
_DISTRACTED_FILTER_F = 0.6 # 0.6Hz, 0.25s ts
|
||||
_DISTRACTED_FILTER_K = 2 * np.pi * _DISTRACTED_FILTER_F * _DTM / (1 + 2 * np.pi * _DISTRACTED_FILTER_F * _DTM)
|
||||
_VARIANCE_FILTER_F = 0.008 # 0.008Hz, 20s ts
|
||||
_VARIANCE_FILTER_K = 2 * np.pi * _VARIANCE_FILTER_F * _DTM / (1 + 2 * np.pi * _VARIANCE_FILTER_F * _DTM)
|
||||
|
||||
|
||||
class MonitorChangeEvent:
|
||||
NO_CHANGE = 0
|
||||
PARAM_ON = 1
|
||||
PARAM_OFF = 2
|
||||
VARIANCE_HIGH = 3
|
||||
VARIANCE_LOW = 4
|
||||
|
||||
class _DriverPose():
|
||||
def __init__(self):
|
||||
self.yaw = 0.
|
||||
|
@ -32,16 +42,30 @@ class _DriverPose():
|
|||
self.yaw_offset = 0.
|
||||
self.pitch_offset = 0.
|
||||
|
||||
def _monitor_hysteresys(variance_level, monitor_valid_prev):
|
||||
var_thr = 0.63 if monitor_valid_prev else 0.37
|
||||
return variance_level < var_thr
|
||||
|
||||
class DriverStatus():
|
||||
def __init__(self, monitor_on):
|
||||
def __init__(self, monitor_on=False):
|
||||
self.pose = _DriverPose()
|
||||
self.monitor_on = monitor_on
|
||||
self.monitor_param_on = monitor_on
|
||||
self.monitor_valid = True # variance needs to be low
|
||||
self.monitor_change_event = MonitorChangeEvent.NO_CHANGE
|
||||
self.awareness = 1.
|
||||
self.driver_distracted = False
|
||||
self.driver_distraction_level = 0.
|
||||
self.variance_high = False
|
||||
self.variance_level = 0.
|
||||
self.ts_last_check = 0.
|
||||
self._set_timers()
|
||||
|
||||
def _reset_filters(self):
|
||||
self.driver_distraction_level = 0.
|
||||
self.variance_level = 0.
|
||||
self.monitor_valid = True
|
||||
|
||||
def _set_timers(self):
|
||||
if self.monitor_on:
|
||||
self.threshold_pre = _DISTRACTED_PRE_TIME / _DISTRACTED_TIME
|
||||
|
@ -64,14 +88,23 @@ class DriverStatus():
|
|||
#print "%02.4f" % np.degrees(pose.pitch), "%02.4f" % np.degrees(pitch_error), "%03.4f" % np.degrees(pose.pitch_offset), metric
|
||||
return 1 if metric > _METRIC_THRESHOLD else 0
|
||||
|
||||
def get_pose(self, driver_monitoring, params):
|
||||
ts = sec_since_boot()
|
||||
|
||||
# don's check for param too often as it's a kernel call
|
||||
if ts - self.ts_last_check > 1.:
|
||||
self.monitor_on = params.get("IsDriverMonitoringEnabled") == "1"
|
||||
self._set_timers()
|
||||
self.ts_last_check = ts
|
||||
def _monitor_change_check(self, monitor_param_on_prev, monitor_valid_prev, monitor_on_prev):
|
||||
if not monitor_param_on_prev and self.monitor_param_on:
|
||||
self._reset_filters()
|
||||
return MonitorChangeEvent.PARAM_ON
|
||||
elif monitor_param_on_prev and not self.monitor_param_on:
|
||||
self._reset_filters()
|
||||
return MonitorChangeEvent.PARAM_OFF
|
||||
elif monitor_on_prev and not self.monitor_valid:
|
||||
return MonitorChangeEvent.VARIANCE_HIGH
|
||||
elif self.monitor_param_on and not monitor_valid_prev and self.monitor_valid:
|
||||
return MonitorChangeEvent.VARIANCE_LOW
|
||||
else:
|
||||
return MonitorChangeEvent.NO_CHANGE
|
||||
|
||||
|
||||
def get_pose(self, driver_monitoring, params):
|
||||
|
||||
self.pose.pitch = driver_monitoring.descriptor[0]
|
||||
self.pose.yaw = driver_monitoring.descriptor[1]
|
||||
|
@ -79,9 +112,28 @@ class DriverStatus():
|
|||
self.pose.yaw_offset = (driver_monitoring.descriptor[3] * _CAMERA_X_CONV + _CAMERA_OFFSET_X) * _CAMERA_FOV_X
|
||||
self.pose.pitch_offset = -driver_monitoring.descriptor[4] * _CAMERA_FOV_Y # positive y is down
|
||||
self.driver_distracted = self._is_driver_distracted(self.pose)
|
||||
# first order filter
|
||||
# first order filters
|
||||
self.driver_distraction_level = (1. - _DISTRACTED_FILTER_K) * self.driver_distraction_level + \
|
||||
_DISTRACTED_FILTER_K * self.driver_distracted
|
||||
self.variance_high = driver_monitoring.std > _STD_THRESHOLD
|
||||
self.variance_level = (1. - _VARIANCE_FILTER_K) * self.variance_level + \
|
||||
_VARIANCE_FILTER_K * self.variance_high
|
||||
|
||||
monitor_param_on_prev = self.monitor_param_on
|
||||
monitor_valid_prev = self.monitor_valid
|
||||
monitor_on_prev = self.monitor_on
|
||||
|
||||
# don't check for param too often as it's a kernel call
|
||||
ts = sec_since_boot()
|
||||
if ts - self.ts_last_check > 1.:
|
||||
self.monitor_param_on = params.get("IsDriverMonitoringEnabled") == "1"
|
||||
self.ts_last_check = ts
|
||||
|
||||
self.monitor_valid = _monitor_hysteresys(self.variance_level, monitor_valid_prev)
|
||||
self.monitor_on = self.monitor_valid and self.monitor_param_on
|
||||
self.monitor_change_event = self._monitor_change_check(monitor_param_on_prev, monitor_valid_prev, monitor_on_prev)
|
||||
self._set_timers()
|
||||
|
||||
|
||||
def update(self, events, driver_engaged, ctrl_active, standstill):
|
||||
|
||||
|
@ -90,20 +142,28 @@ class DriverStatus():
|
|||
if (driver_engaged and self.awareness > 0.) or not ctrl_active:
|
||||
# always reset if driver is in control (unless we are in red alert state) or op isn't active
|
||||
self.awareness = 1.
|
||||
if not ctrl_active:
|
||||
# hold monitor_level constant when control isn't active
|
||||
self.variance_level = 0. if self.monitor_valid else 1.
|
||||
|
||||
if (not self.monitor_on or (self.driver_distraction_level > 0.63 and self.driver_distracted)) and \
|
||||
not (standstill and self.awareness - self.step_change <= self.threshold_prompt):
|
||||
self.awareness = max(self.awareness - self.step_change, -0.1)
|
||||
|
||||
alert = None
|
||||
if self.awareness <= 0.:
|
||||
# terminal red alert: disengagement required
|
||||
events.append(create_event('driverDistracted', [ET.WARNING]))
|
||||
alert = 'driverDistracted' if self.monitor_on else 'driverUnresponsive'
|
||||
elif self.awareness <= self.threshold_prompt:
|
||||
# prompt orange alert
|
||||
events.append(create_event('promptDriverDistracted', [ET.WARNING]))
|
||||
alert = 'promptDriverDistracted' if self.monitor_on else 'promptDriverUnresponsive'
|
||||
elif self.awareness <= self.threshold_pre:
|
||||
# pre green alert
|
||||
events.append(create_event('preDriverDistracted', [ET.WARNING]))
|
||||
alert = 'preDriverDistracted' if self.monitor_on else 'preDriverUnresponsive'
|
||||
if alert is not None:
|
||||
events.append(create_event(alert, [ET.WARNING]))
|
||||
|
||||
self.monitor_change_event = MonitorChangeEvent.NO_CHANGE
|
||||
|
||||
return events
|
||||
|
||||
|
|
|
@ -1,11 +1,11 @@
|
|||
#!/usr/bin/env python
|
||||
import os
|
||||
import zmq
|
||||
|
||||
import numpy as np
|
||||
import math
|
||||
import numpy as np
|
||||
from copy import copy
|
||||
from cereal import log
|
||||
from collections import defaultdict
|
||||
|
||||
from common.realtime import sec_since_boot
|
||||
from common.numpy_fast import interp
|
||||
import selfdrive.messaging as messaging
|
||||
|
@ -303,6 +303,7 @@ class Planner(object):
|
|||
|
||||
self.last_gps_planner_plan = None
|
||||
self.gps_planner_active = False
|
||||
self.perception_state = log.Live20Data.new_message()
|
||||
|
||||
def choose_solution(self, v_cruise_setpoint, enabled):
|
||||
if enabled:
|
||||
|
@ -374,6 +375,7 @@ class Planner(object):
|
|||
self.PP.c_prob = 1.0
|
||||
|
||||
if l20 is not None:
|
||||
self.perception_state = copy(l20.live20)
|
||||
self.last_l20_ts = l20.logMonoTime
|
||||
self.last_l20 = cur_time
|
||||
self.radar_dead = False
|
||||
|
|
|
@ -26,6 +26,7 @@ DIMSV = 2
|
|||
XV, SPEEDV = 0, 1
|
||||
VISION_POINT = -1
|
||||
|
||||
|
||||
class EKFV1D(EKF):
|
||||
def __init__(self):
|
||||
super(EKFV1D, self).__init__(False)
|
||||
|
@ -137,7 +138,8 @@ def radard_thread(gctx=None):
|
|||
|
||||
# run kalman filter only if prob is high enough
|
||||
if PP.lead_prob > 0.7:
|
||||
ekfv.update(speedSensorV.read(PP.lead_dist, covar=PP.lead_var))
|
||||
reading = speedSensorV.read(PP.lead_dist, covar=np.matrix(PP.lead_var))
|
||||
ekfv.update_scalar(reading)
|
||||
ekfv.predict(tsv)
|
||||
ar_pts[VISION_POINT] = (float(ekfv.state[XV]), np.polyval(PP.d_poly, float(ekfv.state[XV])),
|
||||
float(ekfv.state[SPEEDV]), False)
|
||||
|
@ -145,6 +147,7 @@ def radard_thread(gctx=None):
|
|||
ekfv.state[XV] = PP.lead_dist
|
||||
ekfv.covar = (np.diag([PP.lead_var, ekfv.var_init]))
|
||||
ekfv.state[SPEEDV] = 0.
|
||||
|
||||
if VISION_POINT in ar_pts:
|
||||
del ar_pts[VISION_POINT]
|
||||
|
||||
|
|
Binary file not shown.
|
@ -118,7 +118,6 @@ persistent_processes = [
|
|||
'uploader',
|
||||
'ui',
|
||||
'gpsd',
|
||||
'ubloxd',
|
||||
'updated',
|
||||
]
|
||||
|
||||
|
@ -129,7 +128,7 @@ car_started_processes = [
|
|||
'radard',
|
||||
'visiond',
|
||||
'proclogd',
|
||||
'orbd',
|
||||
'ubloxd',
|
||||
]
|
||||
|
||||
def register_managed_process(name, desc, car_started=False):
|
||||
|
@ -298,6 +297,9 @@ def manager_thread():
|
|||
cloudlog.info("manager start")
|
||||
cloudlog.info({"environ": os.environ})
|
||||
|
||||
# save boot log
|
||||
subprocess.call(["./loggerd", "--bootlog"], cwd=os.path.join(BASEDIR, "selfdrive/loggerd"))
|
||||
|
||||
for p in persistent_processes:
|
||||
start_managed_process(p)
|
||||
|
||||
|
|
Binary file not shown.
Binary file not shown.
|
@ -2,7 +2,7 @@
|
|||
import os
|
||||
import zmq
|
||||
from smbus2 import SMBus
|
||||
|
||||
from cereal import log
|
||||
from selfdrive.version import training_version
|
||||
from selfdrive.swaglog import cloudlog
|
||||
import selfdrive.messaging as messaging
|
||||
|
@ -10,9 +10,9 @@ from selfdrive.services import service_list
|
|||
from selfdrive.loggerd.config import ROOT
|
||||
from common.params import Params
|
||||
from common.realtime import sec_since_boot
|
||||
from common.numpy_fast import clip
|
||||
|
||||
import cereal
|
||||
ThermalStatus = cereal.log.ThermalData.ThermalStatus
|
||||
ThermalStatus = log.ThermalData.ThermalStatus
|
||||
|
||||
def read_tz(x):
|
||||
with open("/sys/devices/virtual/thermal/thermal_zone%d/temp" % x) as f:
|
||||
|
@ -71,12 +71,12 @@ _TEMP_THRS_H = [50., 65., 80., 10000]
|
|||
_TEMP_THRS_L = [42.5, 57.5, 72.5, 10000]
|
||||
# fan speed options
|
||||
_FAN_SPEEDS = [0, 16384, 32768, 65535]
|
||||
# max fan speed only allowed if battery if hot
|
||||
# max fan speed only allowed if battery is hot
|
||||
_BAT_TEMP_THERSHOLD = 45.
|
||||
|
||||
def handle_fan(max_temp, bat_temp, fan_speed):
|
||||
new_speed_h = next(speed for speed, temp_h in zip(_FAN_SPEEDS, _TEMP_THRS_H) if temp_h > max_temp)
|
||||
new_speed_l = next(speed for speed, temp_l in zip(_FAN_SPEEDS, _TEMP_THRS_L) if temp_l > max_temp)
|
||||
def handle_fan(max_cpu_temp, bat_temp, fan_speed):
|
||||
new_speed_h = next(speed for speed, temp_h in zip(_FAN_SPEEDS, _TEMP_THRS_H) if temp_h > max_cpu_temp)
|
||||
new_speed_l = next(speed for speed, temp_l in zip(_FAN_SPEEDS, _TEMP_THRS_L) if temp_l > max_cpu_temp)
|
||||
|
||||
if new_speed_h > fan_speed:
|
||||
# update speed if using the high thresholds results in fan speed increment
|
||||
|
@ -164,31 +164,32 @@ def thermald_thread():
|
|||
msg.thermal.usbOnline = bool(int(f.read()))
|
||||
|
||||
# TODO: add car battery voltage check
|
||||
max_temp = max(msg.thermal.cpu0, msg.thermal.cpu1,
|
||||
msg.thermal.cpu2, msg.thermal.cpu3) / 10.0
|
||||
max_cpu_temp = max(msg.thermal.cpu0, msg.thermal.cpu1,
|
||||
msg.thermal.cpu2, msg.thermal.cpu3) / 10.0
|
||||
max_comp_temp = max(max_cpu_temp, msg.thermal.mem / 10., msg.thermal.gpu / 10.)
|
||||
bat_temp = msg.thermal.bat/1000.
|
||||
fan_speed = handle_fan(max_temp, bat_temp, fan_speed)
|
||||
fan_speed = handle_fan(max_cpu_temp, bat_temp, fan_speed)
|
||||
msg.thermal.fanSpeed = fan_speed
|
||||
|
||||
# thermal logic here
|
||||
|
||||
if max_temp < 70.0:
|
||||
thermal_status = ThermalStatus.green
|
||||
if max_temp > 85.0:
|
||||
cloudlog.warning("over temp: %r", max_temp)
|
||||
thermal_status = ThermalStatus.yellow
|
||||
|
||||
# from controls
|
||||
overtemp_proc = any(t > 950 for t in
|
||||
(msg.thermal.cpu0, msg.thermal.cpu1, msg.thermal.cpu2,
|
||||
msg.thermal.cpu3, msg.thermal.mem, msg.thermal.gpu))
|
||||
overtemp_bat = msg.thermal.bat > 60000 # 60c
|
||||
if overtemp_proc or overtemp_bat:
|
||||
# TODO: hysteresis
|
||||
thermal_status = ThermalStatus.red
|
||||
|
||||
if max_temp > 107.0 or msg.thermal.bat >= 63000:
|
||||
# thermal logic with hysterisis
|
||||
if max_cpu_temp > 107. or bat_temp >= 63.:
|
||||
# onroad not allowed
|
||||
thermal_status = ThermalStatus.danger
|
||||
elif max_comp_temp > 95. or bat_temp > 60.:
|
||||
# hysteresis between onroad not allowed and engage not allowed
|
||||
thermal_status = clip(thermal_status, ThermalStatus.red, ThermalStatus.danger)
|
||||
elif max_cpu_temp > 90.0:
|
||||
# hysteresis between engage not allowed and uploader not allowed
|
||||
thermal_status = clip(thermal_status, ThermalStatus.yellow, ThermalStatus.red)
|
||||
elif max_cpu_temp > 85.0:
|
||||
# uploader not allowed
|
||||
thermal_status = ThermalStatus.yellow
|
||||
elif max_cpu_temp > 75.0:
|
||||
# hysteresis between uploader not allowed and all good
|
||||
thermal_status = clip(thermal_status, ThermalStatus.green, ThermalStatus.yellow)
|
||||
else:
|
||||
# all good
|
||||
thermal_status = ThermalStatus.green
|
||||
|
||||
# **** starting logic ****
|
||||
|
||||
|
@ -225,7 +226,7 @@ def thermald_thread():
|
|||
|
||||
# if any CPU gets above 107 or the battery gets above 63, kill all processes
|
||||
# controls will warn with CPU above 95 or battery above 60
|
||||
if msg.thermal.thermalStatus >= ThermalStatus.danger:
|
||||
if thermal_status >= ThermalStatus.danger:
|
||||
# TODO: Add a better warning when this is happening
|
||||
should_start = False
|
||||
|
||||
|
|
|
@ -65,6 +65,8 @@ const int box_w = vwp_w-sbr_w-(bdr_s*2);
|
|||
const int box_h = vwp_h-(bdr_s*2);
|
||||
const int viz_w = vwp_w-(bdr_s*2);
|
||||
const int header_h = 420;
|
||||
const int footer_h = 280;
|
||||
const int footer_y = vwp_h-bdr_s-footer_h;
|
||||
|
||||
const uint8_t bg_colors[][4] = {
|
||||
[STATUS_STOPPED] = {0x07, 0x23, 0x39, 0xff},
|
||||
|
@ -110,6 +112,7 @@ typedef struct UIScene {
|
|||
float curvature;
|
||||
int engaged;
|
||||
bool engageable;
|
||||
bool monitoring_active;
|
||||
|
||||
bool uilayout_sidebarcollapsed;
|
||||
bool uilayout_mapenabled;
|
||||
|
@ -158,6 +161,7 @@ typedef struct UIState {
|
|||
int font_sans_semibold;
|
||||
int font_sans_bold;
|
||||
int img_wheel;
|
||||
int img_face;
|
||||
|
||||
zsock_t *thermal_sock;
|
||||
void *thermal_sock_raw;
|
||||
|
@ -379,6 +383,9 @@ static void ui_init(UIState *s) {
|
|||
assert(s->img_wheel >= 0);
|
||||
s->img_wheel = nvgCreateImage(s->vg, "../assets/img_chffr_wheel.png", 1);
|
||||
|
||||
assert(s->img_face >= 0);
|
||||
s->img_face = nvgCreateImage(s->vg, "../assets/img_driver_face.png", 1);
|
||||
|
||||
// init gl
|
||||
s->frame_program = load_program(frame_vertex_shader, frame_fragment_shader);
|
||||
assert(s->frame_program);
|
||||
|
@ -981,6 +988,31 @@ static void ui_draw_vision_wheel(UIState *s) {
|
|||
nvgFill(s->vg);
|
||||
}
|
||||
|
||||
static void ui_draw_vision_face(UIState *s) {
|
||||
const UIScene *scene = &s->scene;
|
||||
const int face_size = 96;
|
||||
const int face_x = (scene->ui_viz_rx + face_size + (bdr_s * 2));
|
||||
const int face_y = (footer_y + ((footer_h - face_size) / 2));
|
||||
const int face_img_size = (face_size * 1.5);
|
||||
const int face_img_x = (face_x - (face_img_size / 2));
|
||||
const int face_img_y = (face_y - (face_size / 4));
|
||||
float face_img_alpha = scene->monitoring_active ? 1.0f : 0.15f;
|
||||
float face_bg_alpha = scene->monitoring_active ? 0.3f : 0.1f;
|
||||
NVGcolor face_bg = nvgRGBA(0, 0, 0, (255 * face_bg_alpha));
|
||||
NVGpaint face_img = nvgImagePattern(s->vg, face_img_x, face_img_y,
|
||||
face_img_size, face_img_size, 0, s->img_face, face_img_alpha);
|
||||
|
||||
nvgBeginPath(s->vg);
|
||||
nvgCircle(s->vg, face_x, (face_y + (bdr_s * 1.5)), face_size);
|
||||
nvgFillColor(s->vg, face_bg);
|
||||
nvgFill(s->vg);
|
||||
|
||||
nvgBeginPath(s->vg);
|
||||
nvgRect(s->vg, face_img_x, face_img_y, face_img_size, face_img_size);
|
||||
nvgFillPaint(s->vg, face_img);
|
||||
nvgFill(s->vg);
|
||||
}
|
||||
|
||||
static void ui_draw_vision_header(UIState *s) {
|
||||
const UIScene *scene = &s->scene;
|
||||
int ui_viz_rx = scene->ui_viz_rx;
|
||||
|
@ -1000,6 +1032,18 @@ static void ui_draw_vision_header(UIState *s) {
|
|||
ui_draw_vision_wheel(s);
|
||||
}
|
||||
|
||||
static void ui_draw_vision_footer(UIState *s) {
|
||||
const UIScene *scene = &s->scene;
|
||||
int ui_viz_rx = scene->ui_viz_rx;
|
||||
int ui_viz_rw = scene->ui_viz_rw;
|
||||
|
||||
nvgBeginPath(s->vg);
|
||||
nvgRect(s->vg, ui_viz_rx, footer_y, ui_viz_rw, footer_h);
|
||||
|
||||
// Driver Monitoring
|
||||
ui_draw_vision_face(s);
|
||||
}
|
||||
|
||||
static void ui_draw_vision_alert(UIState *s, int va_size, int va_color,
|
||||
const char* va_text1, const char* va_text2) {
|
||||
const UIScene *scene = &s->scene;
|
||||
|
@ -1109,8 +1153,11 @@ static void ui_draw_vision(UIState *s) {
|
|||
} else if (scene->cal_status == CALIBRATION_UNCALIBRATED) {
|
||||
// Calibration Status
|
||||
ui_draw_calibration_status(s);
|
||||
} else {
|
||||
ui_draw_vision_footer(s);
|
||||
}
|
||||
|
||||
|
||||
nvgEndFrame(s->vg);
|
||||
glDisable(GL_BLEND);
|
||||
}
|
||||
|
@ -1399,6 +1446,7 @@ static void ui_update(UIState *s) {
|
|||
s->scene.engaged = datad.enabled;
|
||||
s->scene.engageable = datad.engageable;
|
||||
s->scene.gps_planner_active = datad.gpsPlannerActive;
|
||||
s->scene.monitoring_active = datad.driverMonitoringOn;
|
||||
// printf("recv %f\n", datad.vEgo);
|
||||
|
||||
s->scene.frontview = datad.rearViewCam;
|
||||
|
@ -1634,12 +1682,6 @@ static void* light_sensor_thread(void *args) {
|
|||
|
||||
int SENSOR_LIGHT = 7;
|
||||
|
||||
struct stat buffer;
|
||||
if (stat("/sys/bus/i2c/drivers/cyccg", &buffer) == 0) {
|
||||
LOGD("LeEco light sensor detected");
|
||||
SENSOR_LIGHT = 5;
|
||||
}
|
||||
|
||||
device->activate(device, SENSOR_LIGHT, 0);
|
||||
device->activate(device, SENSOR_LIGHT, 1);
|
||||
device->setDelay(device, SENSOR_LIGHT, ms2ns(100));
|
||||
|
@ -1653,9 +1695,7 @@ static void* light_sensor_thread(void *args) {
|
|||
LOG_100("light_sensor_poll failed: %d", n);
|
||||
}
|
||||
if (n > 0) {
|
||||
if (SENSOR_LIGHT == 5) s->light_sensor = buffer[0].light * 2;
|
||||
else s->light_sensor = buffer[0].light;
|
||||
//printf("new light sensor value: %f\n", s->light_sensor);
|
||||
s->light_sensor = buffer[0].light;
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Binary file not shown.
Loading…
Reference in New Issue