Skip to content

Commit

Permalink
DFLog: make threadsafe
Browse files Browse the repository at this point in the history
  • Loading branch information
meee1 committed Sep 11, 2015
1 parent 9d1d137 commit 9077192
Show file tree
Hide file tree
Showing 9 changed files with 174 additions and 164 deletions.
42 changes: 22 additions & 20 deletions GeoRef/georefimage.cs
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,8 @@ private enum PROCESSING_MODE
private Label label28;
private List<int> JXL_StationIDs = new List<int>();

DFLog dflog = new DFLog();

public Georefimage()
{
InitializeComponent();
Expand Down Expand Up @@ -233,25 +235,25 @@ private Dictionary<long, VehicleLocation> readGPSMsgInLog(string fn)
a++;
string line = sr.ReadLine();

var item = DFLog.GetDFItemFromLine(line, a);
var item = dflog.GetDFItemFromLine(line, a);
// Look for GPS Messages. However GPS Messages do not have Roll, Pitch and Yaw
// So we have to look for one ATT message after having read a GPS one

if (item.msgtype == "GPS")
{
if (!DFLog.logformat.ContainsKey("GPS"))
if (!dflog.logformat.ContainsKey("GPS"))
continue;

int latindex = DFLog.FindMessageOffset("GPS", "Lat");
int lngindex = DFLog.FindMessageOffset("GPS", "Lng");
int altindex = DFLog.FindMessageOffset("GPS", "Alt");
int raltindex = DFLog.FindMessageOffset("GPS", "RAlt");
int latindex = dflog.FindMessageOffset("GPS", "Lat");
int lngindex = dflog.FindMessageOffset("GPS", "Lng");
int altindex = dflog.FindMessageOffset("GPS", "Alt");
int raltindex = dflog.FindMessageOffset("GPS", "RAlt");

VehicleLocation location = new VehicleLocation();

try
{
location.Time = DFLog.GetTimeGPS(line);
location.Time = dflog.GetTimeGPS(line);
location.Lat = double.Parse(item.items[latindex], CultureInfo.InvariantCulture);
location.Lon = double.Parse(item.items[lngindex], CultureInfo.InvariantCulture);
location.RelAlt = double.Parse(item.items[raltindex], CultureInfo.InvariantCulture);
Expand All @@ -275,9 +277,9 @@ private Dictionary<long, VehicleLocation> readGPSMsgInLog(string fn)
}
else if (item.msgtype == "ATT")
{
int Rindex = DFLog.FindMessageOffset("ATT", "Roll");
int Pindex = DFLog.FindMessageOffset("ATT", "Pitch");
int Yindex = DFLog.FindMessageOffset("ATT", "Yaw");
int Rindex = dflog.FindMessageOffset("ATT", "Roll");
int Pindex = dflog.FindMessageOffset("ATT", "Pitch");
int Yindex = dflog.FindMessageOffset("ATT", "Yaw");

currentRoll = float.Parse(item.items[Rindex], CultureInfo.InvariantCulture);
currentPitch = float.Parse(item.items[Pindex], CultureInfo.InvariantCulture);
Expand Down Expand Up @@ -319,21 +321,21 @@ private Dictionary<long, VehicleLocation> readCAMMsgInLog(string fn)
a++;
string line = sr.ReadLine();

var item = DFLog.GetDFItemFromLine(line, a);
var item = dflog.GetDFItemFromLine(line, a);

if (item.msgtype == "CAM")
{
int latindex = DFLog.FindMessageOffset("CAM", "Lat");
int lngindex = DFLog.FindMessageOffset("CAM", "Lng");
int altindex = DFLog.FindMessageOffset("CAM", "Alt");
int raltindex = DFLog.FindMessageOffset("CAM", "RelAlt");
int latindex = dflog.FindMessageOffset("CAM", "Lat");
int lngindex = dflog.FindMessageOffset("CAM", "Lng");
int altindex = dflog.FindMessageOffset("CAM", "Alt");
int raltindex = dflog.FindMessageOffset("CAM", "RelAlt");

int rindex = DFLog.FindMessageOffset("CAM", "Roll");
int pindex = DFLog.FindMessageOffset("CAM", "Pitch");
int yindex = DFLog.FindMessageOffset("CAM", "Yaw");
int rindex = dflog.FindMessageOffset("CAM", "Roll");
int pindex = dflog.FindMessageOffset("CAM", "Pitch");
int yindex = dflog.FindMessageOffset("CAM", "Yaw");

int gtimeindex = DFLog.FindMessageOffset("CAM", "GPSTime");
int gweekindex = DFLog.FindMessageOffset("CAM", "GPSWeek");
int gtimeindex = dflog.FindMessageOffset("CAM", "GPSTime");
int gweekindex = dflog.FindMessageOffset("CAM", "GPSWeek");

VehicleLocation p = new VehicleLocation();

Expand Down
28 changes: 14 additions & 14 deletions Log/DFLog.cs
Original file line number Diff line number Diff line change
Expand Up @@ -134,9 +134,9 @@ public enum events
DATA_PARACHUTE_RELEASED = 51,
}

public static Dictionary<string, Label> logformat = new Dictionary<string, Label>();
public Dictionary<string, Label> logformat = new Dictionary<string, Label>();

public static void Clear()
public void Clear()
{
logformat.Clear();

Expand All @@ -150,7 +150,7 @@ public static void Clear()
gpsstarttime = DateTime.MinValue;
}

public static DateTime GetFirstGpsTime(string fn)
public DateTime GetFirstGpsTime(string fn)
{
using (StreamReader sr = new StreamReader(fn))
{
Expand All @@ -174,7 +174,7 @@ public static DateTime GetFirstGpsTime(string fn)
return DateTime.MinValue;
}

public static List<DFItem> ReadLog(string fn)
public List<DFItem> ReadLog(string fn)
{
List<DFItem> answer = new List<DFItem>();

Expand All @@ -187,15 +187,15 @@ public static List<DFItem> ReadLog(string fn)
}

// current gps time
static DateTime gpstime = DateTime.MinValue;
DateTime gpstime = DateTime.MinValue;
// last time of message
static DateTime lasttime = DateTime.MinValue;
DateTime lasttime = DateTime.MinValue;
// first valid gpstime
static DateTime gpsstarttime = DateTime.MinValue;
DateTime gpsstarttime = DateTime.MinValue;

static int msoffset = 0;
int msoffset = 0;

public static List<DFItem> ReadLog(Stream fn)
public List<DFItem> ReadLog(Stream fn)
{
Clear();
GC.Collect();
Expand Down Expand Up @@ -243,7 +243,7 @@ public static List<DFItem> ReadLog(Stream fn)
return answer;
}

public static DFItem GetDFItemFromLine(string line, int lineno)
public DFItem GetDFItemFromLine(string line, int lineno)
{

//line = line.Replace(",", ",");
Expand Down Expand Up @@ -389,7 +389,7 @@ public static DFItem GetDFItemFromLine(string line, int lineno)
return item;
}

public static void FMTLine(string strLine)
public void FMTLine(string strLine)
{
try
{
Expand All @@ -413,7 +413,7 @@ public static void FMTLine(string strLine)

//FMT, 130, 45, GPS, BIHBcLLeeEefI, Status,TimeMS,Week,NSats,HDop,Lat,Lng,RelAlt,Alt,Spd,GCrs,VZ,T
//GPS, 3, 130040903, 1769, 10, 0.00, -35.3547178, 149.1696673, 885.52, 870.45, 24.56, 321.44, 2.450000, 127615
public static DateTime GetTimeGPS(string gpsline)
public DateTime GetTimeGPS(string gpsline)
{
if (gpsline.StartsWith("GPS") && logformat.Count > 0)
{
Expand Down Expand Up @@ -456,7 +456,7 @@ public static DateTime GetTimeGPS(string gpsline)

public static DateTime gpsTimeToTime(int week, double sec)
{
int leap = 16;
int leap = 17;

// not correct for leap seconds day days weeks seconds
var basetime = new DateTime(1980, 1, 6, 0, 0, 0, DateTimeKind.Utc);
Expand All @@ -466,7 +466,7 @@ public static DateTime gpsTimeToTime(int week, double sec)
return basetime.ToLocalTime();
}

public static int FindMessageOffset(string linetype,string find)
public int FindMessageOffset(string linetype,string find)
{
if (logformat.ContainsKey(linetype))
return Log.DFLog.FindInArray(logformat[linetype].FieldNames, find);
Expand Down
Loading

0 comments on commit 9077192

Please sign in to comment.