Code for autonomous rover for Sparkfun AVC. DataBus won 3rd in 2012 and the same code was used on Troubled Child, a 1986 Jeep Grand Wagoneer to win 1st in 2014.

Dependencies:   mbed Watchdog SDFileSystem DigoleSerialDisp

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers SystemState.h Source File

SystemState.h

00001 #ifndef _SYSTEMSTATE_H
00002 #define _SYSTEMSTATE_H
00003 
00004 #define SSBUF 32 // must be 2^n
00005 
00006 /** System State is the main mechanism for communicating current realtime system state to
00007  * the rest of the system for logging, data display, etc.
00008  */
00009 
00010 #include <stdbool.h>
00011 
00012 /* struct systemState
00013  * structure containing system sensor data
00014  ****** System Status
00015  * millis               number of milliseconds since epoch (or startup)
00016  * current              current draw in amps
00017  * voltage              voltage in volts
00018  ****** Data reported by IMU
00019  * g[3]                 raw 3-axis gyro values; if using 1-axis, then store data in gx
00020  * gTemp                Gyro temperature
00021  * a[3]                 raw 3-axis accelerometer values
00022  * m[3]                 raw 3-axis magnetometer values; if using 2d then store data in mx and my
00023  * gHeading             independently calculated gyro heading in degrees
00024  * cHeading             independently calculated compass heading in degrees
00025  ****** AHRS Estimates
00026  * roll, pitch, yaw     estimated attitude in degrees relative to the world frame
00027  ****** Data reported by GPS
00028  * gpsLatitude          raw GPS latitude in fractional degrees (e.g., 39.123456)
00029  * gpsLongitude         raw GPS longitude in fractional degrees (e.g., -104.123456
00030  * gpsCourse_deg        raw GPS course in degrees
00031  * gpsSpeed_mps         raw GPS speed in m/s
00032  * gpsHDOP              raw GPS Horizontal Dilution of Precision
00033  * gpsSats              raw GPS Satellite fix count
00034  ****** Odometry data
00035  * lrEncDistance        left rear encoder distance since last log update
00036  * rrEncDistance        right rear encoder distance since last log update
00037  * lrEncSpeed           left rear encoder speed 
00038  * rrEncSpeed           right rear encoder speed
00039  * encHeading           estimated heading based on encoder readings
00040  ****** Estimated Position and Heading
00041  * estLagHeading        estimated heading in degrees, lagged to sync with gps
00042  * estHeading           estimated current heading
00043  * estLatitude          estimated latitude in fractional degrees (e.g., 39.123456)
00044  * estLongitude         estimated longitude in fractional degrees (e.g., -104.123456)
00045  * estNorthing          some algorithms use UTM.  Estimated UTM northing
00046  * estEasting           estimated UTM easting
00047  * estX, estY           some algorithms use simple x, y distance from origin (meters)
00048  ****** Waypoint data
00049  * nextWaypoint         integer ID of the next waypoint
00050  * bearing              estimated bearing to next waypoint in degrees
00051  * distance             estimated distance to next waypoint in meters
00052  ****** Control data
00053  * throttle             raw servo setting(units?)
00054  * steering             raw servo setting(units?)
00055  */
00056 typedef struct {
00057     unsigned int millis;
00058     float current, voltage;
00059     int g[3];
00060     float gyro[3];
00061     int gTemp;
00062     int a[3];
00063     int m[3];
00064     float gHeading;
00065     float cHeading;
00066     //float roll, pitch, yaw;
00067     double gpsLatitude;
00068     double gpsLongitude;
00069     float gpsCourse_deg;
00070     float gpsSpeed_mps;
00071     float gpsHDOP;
00072     int gpsSats;
00073     float lrEncDistance, rrEncDistance;
00074     float lrEncSpeed, rrEncSpeed;
00075     float encHeading;
00076     float estHeading;
00077     float estLagHeading;
00078     double estLatitude, estLongitude;
00079     //double estNorthing, estEasting;
00080     float estX, estY;
00081     unsigned short nextWaypoint;
00082     float bearing;
00083     float distance;
00084     float gbias;
00085     float errHeading;
00086     float steerAngle;
00087     float LABrg;
00088     float LAx;
00089     float LAy;
00090 } SystemState;
00091 
00092 void state_clear( SystemState *s );
00093 bool fifo_init(void);
00094 void fifo_reset(void);
00095 bool fifo_available(void);
00096 bool fifo_push(SystemState *s);
00097 SystemState *fifo_first(void);
00098 SystemState *fifo_last(void);
00099 SystemState *fifo_pull(void);
00100 int fifo_getInState(void);
00101 int fifo_getOutState(void);
00102 
00103 #endif