Skip to content

Commit

Permalink
Squashed 'lib/NMEA2000/' changes from 077effa..d3c5680
Browse files Browse the repository at this point in the history
d3c5680 Document update
8a9afe7 Document update
7dce81e Missing updated file
62fdd2d Merge pull request #19 from xslim/patch-1
3010625 Re-send ISO Address claim if request came from 0xff
d451d77 New features and fixes. See. Changes on Readme
372890a Merge pull request #16 from thomasonw/master
47bfdfe User ISO Request Handler - REVISED
9c6912b Library reference update and new example
b5beec2 User ISO Request Handler
8e646fd New PGN 127257. Fix for PGN 127489
f286190 Merge pull request #12 from thomasonw/master
d80b511 Added to API -- Optional message lists
23bc3c6 Merge pull request #2 from ttlappalainen/master
67c140d Some example fixes and changes
3748175 Merge pull request #9 from thomasonw/master
8f5b979 Corrected parsing of DCBatStatus
ac2c890 Corrected Battery Current in ParseN2kPGN127508
86b4662 Merge pull request #1 from ttlappalainen/master
a804b96 Comment update

git-subtree-dir: lib/NMEA2000
git-subtree-split: d3c5680
  • Loading branch information
sarfata committed Sep 7, 2016
1 parent 61cd3a2 commit c16fe10
Show file tree
Hide file tree
Showing 17 changed files with 462 additions and 133 deletions.
Binary file modified Documents/NMEA2000_library_reference.pdf
Binary file not shown.
184 changes: 110 additions & 74 deletions Examples/DataDisplay2/DataDisplay2.ino

Large diffs are not rendered by default.

16 changes: 14 additions & 2 deletions Examples/MessageSender/MessageSender.ino
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ void setup() {
// If you also want to see all traffic on the bus use N2km_ListenAndNode instead of N2km_NodeOnly below
NMEA2000.SetMode(tNMEA2000::N2km_NodeOnly,22);
//NMEA2000.SetDebugMode(tNMEA2000::dm_ClearText); // Uncomment this, so you can test code without CAN bus chips on Arduino Mega
NMEA2000.EnableForward(false); // Disable all msg forwarding to USB (=Serial)
//NMEA2000.EnableForward(false); // Disable all msg forwarding to USB (=Serial)
NMEA2000.Open();
}

Expand Down Expand Up @@ -57,6 +57,12 @@ void SendN2kSlowData() {

if ( SlowDataUpdated+SlowDataUpdatePeriod<millis() ) {
SlowDataUpdated=millis();

SetN2kDCBatStatus(N2kMsg, 1, 12.72);
delay(DelayBetweenSend); NMEA2000.SendMsg(N2kMsg);

SetN2kDCBatStatus(N2kMsg, 0, 12.45, 5.08, CToKelvin(27.15));
delay(DelayBetweenSend); NMEA2000.SendMsg(N2kMsg);

SetN2kTemperatureExt(N2kMsg, 1, 1, N2kts_MainCabinTemperature, ReadCabinTemp(),CToKelvin(21.6));
delay(DelayBetweenSend); NMEA2000.SendMsg(N2kMsg);
Expand All @@ -76,7 +82,10 @@ void SendN2kSlowData() {
SetN2kDCStatus(N2kMsg,1,1,N2kDCt_Alternator,86,91,1420,0.21);
delay(DelayBetweenSend); NMEA2000.SendMsg(N2kMsg);

SetN2kEngineDynamicParam(N2kMsg,1,656000,CToKelvin(86.3),CToKelvin(82.1),14.21,5.67,hToSeconds(2137.55));
SetN2kAttitude(N2kMsg,1,DegToRad(-3.1),DegToRad(2.4),DegToRad(-7.8));
delay(DelayBetweenSend); NMEA2000.SendMsg(N2kMsg);

SetN2kEngineDynamicParam(N2kMsg,1,656000,CToKelvin(86.3),CToKelvin(82.1),14.21,5.67,hToSeconds(2137.55),N2kDoubleNA,N2kDoubleNA,N2kInt8NA,N2kInt8NA,true);
delay(DelayBetweenSend); NMEA2000.SendMsg(N2kMsg);

SetN2kTransmissionParameters(N2kMsg,1,N2kTG_Forward,750000, CToKelvin(65.5),0x6f);
Expand All @@ -88,6 +97,9 @@ void SendN2kSlowData() {
SetN2kGNSS(N2kMsg,1,17555,62000,-60.1,67.5,10.5,N2kGNSSt_GPS,N2kGNSSm_GNSSfix,12,0.8,0.5,15,1,N2kGNSSt_GPS,15,2);
delay(DelayBetweenSend); NMEA2000.SendMsg(N2kMsg);
// Serial.print(millis()); Serial.println(", Temperature send ready");

SetN2kMagneticHeading(N2kMsg, 0, DegToRad(127.5), DegToRad(0.0), DegToRad(7.5));
delay(DelayBetweenSend); NMEA2000.SendMsg(N2kMsg);
}
}

Expand Down
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file not shown.
Binary file not shown.
Original file line number Diff line number Diff line change
@@ -0,0 +1,35 @@
// Demo: NMEA2000 library. NMEA 2000 bus Actisense format listener and sender.
// Sends all bus data to serial1 in Actisense format.
// Send all data received from serial (USB) in Actisense format to the N2kBus.
// Use this e.g. with NMEA Simulator (see. http://www.kave.fi/Apps/index.html) to send simulated data to the bus.

#include <Arduino.h>
#include <NMEA2000_CAN.h>
#include <ActisenseReader.h>

tActisenseReader ActisenseReader;

void setup() {
Serial.begin(115200); // Data from PC
Serial1.begin(115200); // Data to PC
NMEA2000.SetForwardStream(&Serial1);
NMEA2000.SetMode(tNMEA2000::N2km_ListenAndSend);
//NMEA2000.SetForwardType(tNMEA2000::fwdt_Text); // Show in clear text
NMEA2000.Open();

// I had problem to use same Serial stream for reading and sending.
// It worked for a while, but then stopped.
ActisenseReader.SetReadStream(&Serial);
ActisenseReader.SetMsgHandler(HandleStreamN2kMsg);
}

void HandleStreamN2kMsg(const tN2kMsg &N2kMsg) {
// N2kMsg.Print(&Serial);
NMEA2000.SendMsg(N2kMsg,-1);
}

void loop() {
NMEA2000.ParseMessages();
ActisenseReader.ParseMessages();
}

1 change: 1 addition & 0 deletions N2kCANMsg.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@ class tN2kCANMsg
bool Ready; // Ready for handling
bool FreeMsg; // Msg is free for fill up
bool SystemMessage;
bool KnownMessage;
unsigned char LastFrame; // Last received frame on fast packets
unsigned char CopiedLen;

Expand Down
44 changes: 38 additions & 6 deletions N2kMessages.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,37 @@ bool ParseN2kPGN127251(const tN2kMsg &N2kMsg, unsigned char &SID, double &RateOf
return true;
}

//*****************************************************************************
// Attitude
// Input:
// - SID Sequence ID. If your device is e.g. boat speed and heading at same time, you can set same SID for different messages
// to indicate that they are measured at same time.
// - Yaw Heading in radians.
// - Pitch Pitch in radians. Positive, when your bow rises.
// - Roll Roll in radians. Positive, when tilted right.
// Output:
// - N2kMsg NMEA2000 message ready to be send.
void SetN2kPGN127257(tN2kMsg &N2kMsg, unsigned char SID, double Yaw, double Pitch, double Roll) {
N2kMsg.SetPGN(127257L);
N2kMsg.Priority=2;
N2kMsg.AddByte(SID);
N2kMsg.Add2ByteDouble(Yaw,0.0001);
N2kMsg.Add2ByteDouble(Pitch,0.0001);
N2kMsg.Add2ByteDouble(Roll,0.0001);
N2kMsg.AddByte(0xff); // Reserved
}

bool ParseN2kPGN127257(const tN2kMsg &N2kMsg, unsigned char &SID, double &Yaw, double &Pitch, double &Roll){
if (N2kMsg.PGN!=127257L) return false;

int Index=0;
Yaw=N2kMsg.Get2ByteDouble(0.001,Index);
Pitch=N2kMsg.Get2ByteDouble(0.001,Index);
Roll=N2kMsg.Get2ByteDouble(0.001,Index);

return true;
}

//*****************************************************************************
// Engine rapid param
void SetN2kPGN127488(tN2kMsg &N2kMsg, unsigned char EngineInstance, double EngineSpeed,
Expand Down Expand Up @@ -142,6 +173,7 @@ bool ParseN2kPGN127488(const tN2kMsg &N2kMsg, unsigned char &EngineInstance, dou
}

//*****************************************************************************
// Engine parameters dynamic
void SetN2kPGN127489(tN2kMsg &N2kMsg, unsigned char EngineInstance, double EngineOilPress, double EngineOilTemp, double EngineCoolantTemp, double AltenatorVoltage,
double FuelRate, double EngineHours, double EngineCoolantPress, double EngineFuelPress, int8_t EngineLoad, int8_t EngineTorque,
bool flagCheckEngine,
Expand All @@ -162,8 +194,6 @@ void SetN2kPGN127489(tN2kMsg &N2kMsg, unsigned char EngineInstance, double Engin
N2kMsg.Add2ByteUDouble(EngineCoolantPress, 100);
N2kMsg.Add2ByteUDouble(EngineFuelPress, 1000);
N2kMsg.AddByte(0xff); // reserved
N2kMsg.Add2ByteInt(0x0000); // Discrete Status 1
N2kMsg.Add2ByteInt(0x0000); // Discrete Status 2

int engineStatus1P1 = B00000000;
int engineStatus1P2 = B00000000;
Expand Down Expand Up @@ -194,6 +224,8 @@ void SetN2kPGN127489(tN2kMsg &N2kMsg, unsigned char EngineInstance, double Engin
if (flagSubThrottle) engineStatus2 |= B00100000;
if (flagNeutralStartProtect) engineStatus2 |= B01000000;
if (flagEngineShuttingDown) engineStatus2 |= B10000000;
N2kMsg.Add2ByteInt(engineStatus1P2<<8 | engineStatus1P1); // Discrete Status 1
N2kMsg.Add2ByteInt(engineStatus2); // Discrete Status 1

N2kMsg.AddByte(EngineLoad);
N2kMsg.AddByte(EngineTorque);
Expand Down Expand Up @@ -333,7 +365,7 @@ bool ParseN2kPGN127508(const tN2kMsg &N2kMsg, unsigned char &BatteryInstance, do
int Index=0;
BatteryInstance=N2kMsg.GetByte(Index);
BatteryVoltage=N2kMsg.Get2ByteDouble(0.01,Index);
BatteryCurrent=N2kMsg.Get2ByteDouble(0.01,Index);
BatteryCurrent=N2kMsg.Get2ByteDouble(0.1,Index);
BatteryTemperature=N2kMsg.Get2ByteUDouble(0.01,Index);
SID=N2kMsg.GetByte(Index);

Expand Down Expand Up @@ -953,7 +985,7 @@ void SetN2kPGN130310(tN2kMsg &N2kMsg, unsigned char SID, double WaterTemperature
N2kMsg.AddByte(SID);
N2kMsg.Add2ByteUDouble(WaterTemperature,0.01);
N2kMsg.Add2ByteUDouble(OutsideAmbientAirTemperature,0.01);
N2kMsg.Add2ByteUDouble(AtmosphericPressure,1);
N2kMsg.Add2ByteUDouble(AtmosphericPressure,100);
N2kMsg.AddByte(0xff); // reserved
}

Expand All @@ -964,7 +996,7 @@ bool ParseN2kPGN130310(const tN2kMsg &N2kMsg, unsigned char &SID, double &WaterT
SID=N2kMsg.GetByte(Index);
WaterTemperature=N2kMsg.Get2ByteUDouble(0.01,Index);
OutsideAmbientAirTemperature=N2kMsg.Get2ByteUDouble(0.01,Index);
AtmosphericPressure=N2kMsg.Get2ByteUDouble(1,Index);
AtmosphericPressure=N2kMsg.Get2ByteUDouble(100,Index);

return true;
}
Expand All @@ -980,7 +1012,7 @@ void SetN2kPGN130311(tN2kMsg &N2kMsg, unsigned char SID, tN2kTempSource TempInst
N2kMsg.AddByte(((HumidityInstance) & 0x03)<<6 | (TempInstance & 0x3f));
N2kMsg.Add2ByteUDouble(Temperature,0.01);
N2kMsg.Add2ByteDouble(Humidity,0.004);
N2kMsg.Add2ByteUDouble(AtmosphericPressure,1);
N2kMsg.Add2ByteUDouble(AtmosphericPressure,100);
}

//*****************************************************************************
Expand Down
62 changes: 58 additions & 4 deletions N2kMessages.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,12 @@ inline double RadToDeg(double v) { return v*180.0/3.1415926535897932384626433832
inline double DegToRad(double v) { return v/180.0*3.1415926535897932384626433832795; }
inline double CToKelvin(double v) { return v+273.15; }
inline double KelvinToC(double v) { return v-273.15; }
inline double FToKelvin(double v) { return (v-32)*5.0/9.0+273.15; }
inline double KelvinToF(double v) { return (v-273.15)*9.0/5.0+32; }
inline double mBarToPascal(double v) { return v*100; }
inline double PascalTomBar(double v) { return v/100; }
inline double hPAToPascal(double v) { return v*100; }
inline double PascalTohPA(double v) { return v/100; }
inline double AhToCoulomb(double v) { return v*3600; }
inline double CoulombToAh(double v) { return v/3600; }
inline double hToSeconds(double v) { return v*3600; }
Expand Down Expand Up @@ -327,6 +331,27 @@ inline bool ParseN2kRateOfTurn(const tN2kMsg &N2kMsg, unsigned char &SID, double
return ParseN2kPGN127251(N2kMsg,SID,RateOfTurn);
}

//*****************************************************************************
// Attitude
// Input:
// - SID Sequence ID. If your device is e.g. boat speed and heading at same time, you can set same SID for different messages
// to indicate that they are measured at same time.
// - Yaw Heading in radians.
// - Pitch Pitch in radians. Positive, when your bow rises.
// - Roll Roll in radians. Positive, when tilted right.
// Output:
// - N2kMsg NMEA2000 message ready to be send.
void SetN2kPGN127257(tN2kMsg &N2kMsg, unsigned char SID, double Yaw, double Pitch, double Roll);

inline void SetN2kAttitude(tN2kMsg &N2kMsg, unsigned char SID, double Yaw, double Pitch, double Roll) {
SetN2kPGN127257(N2kMsg,SID, Yaw, Pitch, Roll);
}

bool ParseN2kPGN127257(const tN2kMsg &N2kMsg, unsigned char &SID, double &Yaw, double &Pitch, double &Roll);
inline bool ParseN2kAttitude(const tN2kMsg &N2kMsg, unsigned char &SID, double &Yaw, double &Pitch, double &Roll) {
return ParseN2kPGN127257(N2kMsg,SID, Yaw, Pitch, Roll);
}

//*****************************************************************************
// Engine parameters rapid
// Input:
Expand Down Expand Up @@ -431,20 +456,49 @@ inline bool ParseN2kEngineDynamicParam(const tN2kMsg &N2kMsg, unsigned char &Eng
// Output:
// - N2kMsg NMEA2000 message ready to be send.
void SetN2kPGN127493(tN2kMsg &N2kMsg, unsigned char EngineInstance, tN2kTransmissionGear TransmissionGear,
double OilPressure, double OilTemperature, unsigned char DiscreteStatus1);
double OilPressure, double OilTemperature, unsigned char DiscreteStatus1=0);

inline void SetN2kTransmissionParameters(tN2kMsg &N2kMsg, unsigned char EngineInstance, tN2kTransmissionGear TransmissionGear,
double OilPressure, double OilTemperature, unsigned char DiscreteStatus1) {
double OilPressure, double OilTemperature, unsigned char DiscreteStatus1=0) {
SetN2kPGN127493(N2kMsg, EngineInstance, TransmissionGear, OilPressure, OilTemperature, DiscreteStatus1);
}

inline void SetN2kTransmissionParameters(tN2kMsg &N2kMsg, unsigned char EngineInstance, tN2kTransmissionGear TransmissionGear,
double OilPressure, double OilTemperature,
bool flagCheck, bool flagOverTemp, bool flagLowOilPressure=false, bool flagLowOilLevel=false,
bool flagSailDrive=false) {
unsigned char DiscreteStatus1=0;

if (flagCheck) DiscreteStatus1 |= B00000001;
if (flagOverTemp) DiscreteStatus1 |= B00000010;
if (flagLowOilPressure) DiscreteStatus1 |= B00000100;
if (flagLowOilLevel) DiscreteStatus1 |= B00001000;
if (flagSailDrive) DiscreteStatus1 |= B00010000;
SetN2kPGN127493(N2kMsg, EngineInstance, TransmissionGear, OilPressure, OilTemperature,DiscreteStatus1);
}

bool ParseN2kPGN127493(const tN2kMsg &N2kMsg, unsigned char &EngineInstance, tN2kTransmissionGear &TransmissionGear,
double &OilPressure, double &OilTemperature, unsigned char &DiscreteStatus1);
inline bool ParseN2kTransmissionParameters(const tN2kMsg &N2kMsg, unsigned char &EngineInstance, tN2kTransmissionGear &TransmissionGear,
double &OilPressure, double &OilTemperature, unsigned char &DiscreteStatus1) {
return ParseN2kPGN127493(N2kMsg, EngineInstance, TransmissionGear, OilPressure, OilTemperature, DiscreteStatus1);
}

inline bool ParseN2kTransmissionParameters(const tN2kMsg &N2kMsg, unsigned char &EngineInstance, tN2kTransmissionGear &TransmissionGear,
double &OilPressure, double &OilTemperature,
bool &flagCheck, bool &flagOverTemp, bool &flagLowOilPressure, bool &flagLowOilLevel,
bool &flagSailDrive) {
unsigned char DiscreteStatus1;
bool ret=ParseN2kPGN127493(N2kMsg, EngineInstance, TransmissionGear, OilPressure, OilTemperature, DiscreteStatus1);
if (ret) {
flagCheck = ((DiscreteStatus1&B00000001)!=0);
flagOverTemp = ((DiscreteStatus1&B00000010)!=0);
flagLowOilPressure = ((DiscreteStatus1&B00000100)!=0);
flagLowOilLevel = ((DiscreteStatus1&B00001000)!=0);
flagSailDrive = ((DiscreteStatus1&B00010000)!=0);
}
return ret;
}
//*****************************************************************************
// Fluid level
// Input:
Expand Down Expand Up @@ -517,11 +571,11 @@ inline void SetN2kDCBatStatus(tN2kMsg &N2kMsg, unsigned char BatteryInstance, do
SetN2kPGN127508(N2kMsg,BatteryInstance,BatteryVoltage,BatteryCurrent,BatteryTemperature,SID);
}

bool ParseN2kPGN130312(const tN2kMsg &N2kMsg, unsigned char &BatteryInstance, double &BatteryVoltage, double &BatteryCurrent,
bool ParseN2kPGN127508(const tN2kMsg &N2kMsg, unsigned char &BatteryInstance, double &BatteryVoltage, double &BatteryCurrent,
double &BatteryTemperature, unsigned char &SID);
inline bool ParseN2kDCBatStatus(const tN2kMsg &N2kMsg, unsigned char &BatteryInstance, double &BatteryVoltage, double &BatteryCurrent,
double &BatteryTemperature, unsigned char &SID) {
return ParseN2kPGN130312(N2kMsg, BatteryInstance, BatteryVoltage, BatteryCurrent, BatteryTemperature, SID);
return ParseN2kPGN127508(N2kMsg, BatteryInstance, BatteryVoltage, BatteryCurrent, BatteryTemperature, SID);
}


Expand Down
4 changes: 2 additions & 2 deletions N2kMsg.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -560,7 +560,7 @@ void PrintBuf(Stream *port, unsigned char len, const unsigned char *pData) {

//*****************************************************************************
void tN2kMsg::Print(Stream *port, bool NoData) const {
if (!IsValid()) return;
if (port==0 || !IsValid()) return;
port->print(F("Pri:")); port->print(Priority);
port->print(F(" PGN:")); port->print(PGN);
port->print(F(" Source:")); port->print(Source);
Expand Down Expand Up @@ -595,7 +595,7 @@ void tN2kMsg::SendInActisenseFormat(Stream *port) const {
byte CheckSum;
unsigned char ActisenseMsgBuf[MaxActisenseMsgBuf];

if (!IsValid()) return;
if (port==0 || !IsValid()) return;
// Serial.print("freeMemory()="); Serial.println(freeMemory());

ActisenseMsgBuf[msgIdx++]=Escape;
Expand Down
Loading

0 comments on commit c16fe10

Please sign in to comment.