Rushduino GPS MCE V1.3
(Paper) maps rule the world. Give me a map, and everything will be ok. Unfortunately, the past made me realize that my map is wrong. Not wrong in general but wrong in the details. Wrong details however will confuse you if you rely on your map.This is where openstreetmap (OSM) comes in handy. I decided to correct my map myself.
Mapping for OSM does not require you to use a GPS device, but it comes in handy. While looking for a suitable GPS device I found this cool GPS board and bougt it from flyduino.net.
52€ is ok for an complete board with SD - Card capability. And I am also quite interested in Quadcopters / Multicopters for which it was designed originally.
I found the board to be poorly documented.
There is some basic text in the original shop.
There is a video on vimeo.
The "latest" source code can be found here.
The "latest" source code is based on this code here ( I2C_GPS_NAV) which you need to compile.
On Board you find:
- ATMEGA328p (with Arduino Bootloader)
- GPS: GTPA010 (MEDIATEK-3329)
- MicroSD Card slot
- 3 LEDs: Power, GPS Fix, BST ("basic sanity test")
- 6 Pin solder joint (unconnected) which probably is the ISP connection (JUST a guess, did not check it!)
- It looks like a 3.3V voltage regulator for the SD-Card. See image above C4 C5
- Serial Connection to the GPS (NMEA message at 10Hz/115200bps)
- FTDI Connection (Serial Port of the ATMEGA328p)
- I2C Connection to the ATMEGA328p (which apparantly acts - according to the firmeware - as a I2C slave)
- NOTE: All GND Pins and 5V pins are connected. There is no overcurrent, overvoltage or polarity protection.
- NOTE: You can talk NMEA to the GPS via "GPS-Serial" and talk to the ATMEGA via "FTDI". The ATMEGA itself also talks to the GPS. So "GPS-Serial Tx" is connected to "FTDI Rx" and "GPS-Serial Rx" is "FTDI Tx". With the Arduino compatibel serial-programmer I used, I had to unplug the FTDI connection to get the board running (to get the GPS talking to the ATMEGA).
Turning the devie on to use it "bare bone" leaves you pretty much standing in the rain. I expected the board to start logging the position but nothing happened. Apparanty the Power LED or the circuit is bad. It looks like it got too much current, and now its broken. Lukily the rest of the board seems to be ok. After I did not know about the firmeware installed I downloaded the "latest code". Unfortunately the "latest code" (Version 20) does not work, nor does it compile with the current version 21 of the I2C_GPS_NAV code. Well, pretty annoying. Thats exactly what I did NOT want.
In order to get the code running,
- copy the Rushdiono specific stuff from the given config.h to the one from I2C_GPS_NAV
- uncomment #define RUSHDUINO_GPS in config.h
- uncomment one of the three depending on your needs:
- #define GPS_PROMINI_SERIAL // direct serial link from GPS to FC - record on SD
- #define GPS_I2C_WITH_SD // Not include PH and RTH (Based on EOSBANDI R11) - record on SD
- #define GPS_I2C_WITHOUT_SD // include PH and RTH but not SD (Based on EOSBANDI R33)
- NOTE: I cannot compile the GPS_I2C_WITHOUT_SD. I dit not investigate the errors since I use GPS_I2C_WITH_SD
- replace the ISC_GPS_NAV.ino with the Rusduino version
- replace #include <Wire.h> with #include "WireMW.h" in ISC_GPS_NAV.ino
Anyway I found the GPS Logging function RecordToSD() to be a mess. In my eyes the "latest code" can not work properly. See my version of ISC_GPS_NAV.ino below.
NOTE: you should replace <altitudeMode>relativeToSeaFloor</altitudeMode> with <gx:altitudeMode>relativeToSeaFloor</gx:altitudeMode>
So far the Firmware is a mess but it seems to work for my needs.
More to come soon...
/*******************************************************************************************************************************
* I2CGPS - Inteligent GPS and NAV module for MultiWii by EOSBandi
* V2.0
*
* This program implements position hold and navigational functions for MultiWii by offloading caclulations and gps parsing
* into a secondary arduino processor connected to the MultiWii via i2c.
* Once activated it outputs desired banking in a lat/lon coordinate system, which can be easily rotated into the copter's frame of reference.
* Need an updated version of Wire library, since current one does not handle repeated start in slave mode.
* also uses PI and PID libraries from the Arduplane team
*
* Navigation and Position hold routines and PI/PID libraries are based on code and ideas from the Arducopter team:
* Jason Short,Randy Mackay, Pat Hickey, Jose Julio, Jani Hirvinen
* Andrew Tridgell, Justin Beech, Adam Rivera, Jean-Louis Naudin, Roberto Navoni
* Status blink code from Guru_florida
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* any later version. see <http://www.gnu.org/licenses/>
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
***********************************************************************************************************************************/
#define VERSION 20 //Software version for cross checking
#include "WireMW.h"
#include <AC_PID.h>
#include <APM_PI.h>
#include <avr/pgmspace.h>
#include "registers.h" //Register definitions
#include "config.h"
#if defined (RUSHDUINO_GPS)
#include <SD.h>
#endif
#define REG_MAP_SIZE sizeof(i2c_dataset) //size of register map
#define MAX_SENT_BYTES 0x0C //maximum amount of data that I could receive from a master device (register, plus 11 byte waypoint data)
#define LAT 0
#define LON 1
///////////////////////////////////////////////////////////////////////////////////////////////////
// Which command I got from the host ? in GPSMode variable
#define GPSMODE_NONAV 0 // no navigation
#define GPSMODE_HOLD 1 // pos hold
#define GPSMODE_WP 2 // wp navigation
///////////////////////////////////////////////////////////////////////////////////////////////////
// Navigation state machine states (nav_mode)
#define NAV_MODE_NONE 0
#define NAV_MODE_POSHOLD 1
#define NAV_MODE_WP 2
// Convert deg*100 to radians
#define RADX100 0.000174532925
//Blink feedback, by guru_florida
#define BLINK_INTERVAL 90
typedef struct {
uint8_t new_data:1;
uint8_t gps2dfix:1;
uint8_t gps3dfix:1;
uint8_t wp_reached:1;
uint8_t numsats:4;
} STATUS_REGISTER;
typedef struct {
uint8_t command:4;
uint8_t wp:4;
} COMMAND_REGISTER;
typedef struct {
uint8_t active_wp:4;
uint8_t pervious_wp:4;
} WAYPOINT_REGISTER;
typedef struct {
long lat; //degree*10 000 000
long lon; //degree*10 000 000
} GPS_COORDINATES;
typedef struct {
GPS_COORDINATES position; //GPS coordinate of the waypoint
uint16_t altitude; //altitude of the waypoint in meters (altitude is relative to the startup altitude)
uint8_t flags; //to be defined
} WAYPOINT;
typedef struct {
//Status and command registers
STATUS_REGISTER status; // 0x00 status register
COMMAND_REGISTER command; // 0x01 command register
WAYPOINT_REGISTER wp_register; // 0x02 waypoint register (current, previus)
uint8_t sw_version; // 0x03 Version of the I2C_GPS sw
uint8_t res3; // 0x04 reserved for future use
uint8_t res4; // 0x05 reserved for future use
uint8_t res5; // 0x06 reserved for future use
//GPS & navigation data
GPS_COORDINATES gps_loc; // current location (8 byte) lat,lon
int16_t nav_lat; // The desired bank towards North (Positive) or South (Negative) 1 deg = 100 max 30deg (3000)
int16_t nav_lon; // The desired bank towards East (Positive) or West (Negative) 1 deg = 100 max 30deg (3000)
uint32_t wp_distance; // distance to active coordinates (calculated) in cm
int16_t wp_target_bearing; // direction to active coordinates (calculated) 1deg = 10 / -1800 - 1800
int16_t nav_bearing; // crosstrack corrected navigational bearing 1deg = 10
int16_t home_to_copter_bearing; // 1deg = 10
uint16_t distance_to_home; // distance to home in cm
uint16_t ground_speed; // ground speed from gps m/s*100
int16_t altitude; // gps altitude
uint16_t ground_course; // GPS ground course
uint16_t res6; // reserved for future use
uint32_t time; // UTC Time from GPS
//Parameters
uint8_t nav_crosstrack_gain; // Crosstrack gain *100 (1 - 0.01 , 100 - 1)
uint8_t nav_speed_min; // minimum speed for navigation cm/s
uint16_t nav_speed_max; // maxiumum speed for navigation cm/s
uint16_t nav_bank_max; // maximum banking 1deg = 100, 30deg = 3000
uint16_t wp_radius; // waypoint radius, if we within this radius, then we considered that the wp is reached in cm
uint8_t nav_flags; // navigational flags to be defined
//PID values
uint8_t poshold_p; // *100
uint8_t poshold_i; // *100
uint8_t poshold_imax; // *1
uint8_t poshold_rate_p; // *10
uint8_t poshold_rate_i; // *100
uint8_t poshold_rate_d; // *1000
uint8_t poshold_rate_imax; // *1
uint8_t nav_p; // *10
uint8_t nav_i; // *100
uint8_t nav_d; // *1000
uint8_t nav_imax; // *1
WAYPOINT gps_wp[16]; // 16 waypoints, WP#0 is RTH position
} I2C_REGISTERS;
static I2C_REGISTERS i2c_dataset;
static GPS_COORDINATES _target; //internal target location register
static uint8_t receivedCommands[MAX_SENT_BYTES];
static uint8_t new_command; //new command received (!=0)
//////////////////////////////////////////////////////////////////////////////
// Rushduino GPS variable
#if defined (RUSHDUINO_GPS)
const uint8_t chipSelect = 10;
uint8_t SDPresent = 0;
boolean LedState = LOW;
File dataFile;
String dataString = "";
String tmpString = "";
char* FileName = "GPSLog00.kml";
uint32_t EndCoordinateLine = 0;
//static uint32_t _timemem = 0;
prog_char string_0[] PROGMEM = "<?xml version=\"1.0\" encoding=\"UTF-8\"?>";
prog_char string_1[] PROGMEM = "<kml xmlns=\"http://www.opengis.net/kml/2.2\">";
prog_char string_2[] PROGMEM = "<Document>";
prog_char string_3[] PROGMEM = "<Placemark>";
prog_char string_4[] PROGMEM = "<LineString>";
prog_char string_5[] PROGMEM = "<extrude>1</extrude>";
prog_char string_6[] PROGMEM = "<altitudeMode>relativeToSeaFloor</altitudeMode>";
prog_char string_7[] PROGMEM = "<coordinates>";
#define STRINGTABLELENGTH 8
PROGMEM const char *string_table[] = // change "string_table" name to suit
{
string_0,
string_1,
string_2,
string_3,
string_4,
string_5,
string_6,
string_7
};
char testbuffer[60];
#endif
//////////////////////////////////////////////////////////////////////////////
// Variables and controllers
//PID controllers
#if defined(GPS_I2C_WITHOUT_SD)
APM_PI pi_poshold_lat(POSHOLD_P, POSHOLD_I, POSHOLD_IMAX * 100);
APM_PI pi_poshold_lon(POSHOLD_P, POSHOLD_I, POSHOLD_IMAX * 100);
AC_PID pid_poshold_rate_lat(POSHOLD_RATE_P, POSHOLD_RATE_I, POSHOLD_RATE_D, POSHOLD_RATE_IMAX * 100);
AC_PID pid_poshold_rate_lon(POSHOLD_RATE_P, POSHOLD_RATE_I, POSHOLD_RATE_D, POSHOLD_RATE_IMAX * 100);
AC_PID pid_nav_lat(NAV_P,NAV_I,NAV_D,NAV_IMAX * 100);
AC_PID pid_nav_lon(NAV_P,NAV_I,NAV_D,NAV_IMAX * 100);
#endif
// used to track the elapsed time between GPS reads
static uint32_t nav_loopTimer;
// Delta Time in milliseconds for navigation computations, updated with every good GPS read
static float dTnav;
//Actual navigation mode, this needed since we swith to poshold ence arrived at home
static int8_t nav_mode = NAV_MODE_NONE; //Navigation mode
static int16_t x_actual_speed = 0;
static int16_t y_actual_speed = 0;
static int32_t last_longitude = 0;
static int32_t last_latitude = 0;
static int16_t x_rate_d;
static int16_t y_rate_d;
// this is used to offset the shrinking longitude as we go towards the poles
static float GPS_scaleLonDown;
static float GPS_scaleLonUp;
// The difference between the desired rate of travel and the actual rate of travel
// updated after GPS read - 5-10hz
static int16_t x_rate_error;
static int16_t y_rate_error;
static int32_t long_error, lat_error;
// The desired bank towards North (Positive) or South (Negative)
static int16_t nav_lat;
// The desired bank towards East (Positive) or West (Negative)
static int16_t nav_lon;
//Used for rotation calculations for GPS nav vector
static float sin_yaw_y;
static float cos_yaw_x;
//Currently used WP
static int32_t GPS_WP_latitude,GPS_WP_longitude;
static uint16_t GPS_WP_altitude;
static uint8_t GPS_WP_flags;
//Actual position for calculations
static int32_t GPS_latitude,GPS_longitude;
////////////////////////////////////////////////////////////////////////////////
// Location & Navigation
////////////////////////////////////////////////////////////////////////////////
// This is the angle from the copter to the "next_WP" location in degrees * 100
static int32_t target_bearing;
// This is the angle from the copter to the "next_WP" location
// with the addition of Crosstrack error in degrees * 100
static int32_t nav_bearing;
// saves the bearing at takeof (1deg = 1) used to rotate to takeoff direction when arrives at home
static int16_t nav_takeoff_bearing;
////////////////////////////////////////////////////////////////////////////////
// Crosstrack
////////////////////////////////////////////////////////////////////////////////
// deg * 100, The original angle to the next_WP when the next_WP was set
// Also used to check when we pass a WP
static int32_t original_target_bearing;
// The amount of angle correction applied to target_bearing to bring the copter back on its optimum path
static int16_t crosstrack_error;
////////////////////////////////////////////////////////////////////////////////
// The location of the copter in relation to home, updated every GPS read (1deg - 100)
static int32_t home_to_copter_bearing;
// distance between plane and home in cm
static int32_t home_distance;
// distance between plane and next_WP in cm
static int32_t wp_distance;
// used for slow speed wind up when start navigation;
static int16_t waypoint_speed_gov;
// this is the navigation mode what is commanded
static uint8_t GPSMode = GPSMODE_NONAV;
////////////////////////////////////////////////////////////////////////////////////
// Blink code variables
//
static uint32_t lastframe_time = 0;
#if !defined(RUSHDUINO_GPS)
static uint32_t _statusled_timer = 0;
static int8_t _statusled_blinks = 0;
static boolean _statusled_state = 0;
#endif
////////////////////////////////////////////////////////////////////////////////////
// moving average filter variables
//
static uint8_t GPS_filter_index = 0;
static int32_t GPS_filter[2][GPS_FILTER_VECTOR_LENGTH];
static int32_t GPS_filter_sum[2];
static int32_t GPS_read[2];
static int32_t GPS_filtered[2];
static int32_t GPS_degree[2]; //the lat lon degree without any decimals (lat/10 000 000)
////////////////////////////////////////////////////////////////////////////////////
// get bearing from pos1 to pos2, returns an 1deg = 100 precision
//
int32_t GPS_bearing(int32_t lat1, int32_t lon1, int32_t lat2, int32_t lon2)
{
float off_x = (float)lon2 - lon1;
float off_y = ((float)(lat2 - lat1)) * GPS_scaleLonUp;
float bearing = 9000.0f + atan2(-off_y, off_x) * 5729.57795f; //Convert the output redians to 100xdeg
if (bearing < 0) bearing += 36000;
return bearing;
}
////////////////////////////////////////////////////////////////////////////////////
// Calculate our current speed vector from gps position data
//
static void GPS_calc_velocity( int32_t gps_latitude, int32_t gps_longitude){
static int16_t x_speed_old = 0;
static int16_t y_speed_old = 0;
// y_GPS_speed positve = Up
// x_GPS_speed positve = Right
// initialise last_longitude and last_latitude
if( last_longitude == 0 && last_latitude == 0 ) {
last_longitude = gps_longitude;
last_latitude = gps_latitude;
}
float tmp = 1.0/dTnav;
x_actual_speed = (float)(gps_longitude - last_longitude) * GPS_scaleLonDown * tmp;
y_actual_speed = (float)(gps_latitude - last_latitude) * tmp;
x_actual_speed = (x_actual_speed + x_speed_old) / 2;
y_actual_speed = (y_actual_speed + y_speed_old) / 2;
x_speed_old = x_actual_speed;
y_speed_old = y_actual_speed;
last_longitude = gps_longitude;
last_latitude = gps_latitude;
}
////////////////////////////////////////////////////////////////////////////////////
// Check if we missed the destination somehow
//
static bool check_missed_wp()
{
int32_t temp;
temp = target_bearing - original_target_bearing;
temp = wrap_18000(temp);
return (abs(temp) > 10000); // we passed the waypoint by 100 degrees
}
////////////////////////////////////////////////////////////////////////////////////
// Utilities
//
int32_t wrap_18000(int32_t error)
{
if (error > 18000) error -= 36000;
if (error < -18000) error += 36000;
return error;
}
int32_t wrap_36000(int32_t angle)
{
if (angle > 36000) angle -= 36000;
if (angle < 0) angle += 36000;
return angle;
}
////////////////////////////////////////////////////////////////////////////////////
// this is used to offset the shrinking longitude as we go towards the poles
// It's ok to calculate this once per waypoint setting, since it changes a little within the reach of a multicopter
//
void GPS_calc_longitude_scaling(int32_t lat)
{
float rads = (abs((float)lat) / 10000000.0) * 0.0174532925;
GPS_scaleLonDown = cos(rads);
GPS_scaleLonUp = 1.0f / cos(rads);
}
////////////////////////////////////////////////////////////////////////////////////
// Get distance between two points in cm
//
uint32_t GPS_distance_cm(int32_t lat1, int32_t lon1, int32_t lat2, int32_t lon2) {
float dLat = (lat2 - lat1); // difference of latitude in 1/10 000 000 degrees
float dLon = (float)(lon2 - lon1) * GPS_scaleLonDown;
float dist = sqrt(sq(dLat) + sq(dLon)) * 1.113195;
return dist;
}
#if defined(GPS_I2C_WITHOUT_SD)
////////////////////////////////////////////////////////////////////////////////////
// Sets the waypoint to navigate, reset neccessary variables and calculate initial values
// Waypoint 16 is a virtual waypoint, it's a pos hold
void GPS_set_next_wp(uint8_t wp_number)
{
if (wp_number > 16) { return; } //Do nothing with a wrong WP number
if (wp_number <=15 ) {
GPS_WP_latitude = i2c_dataset.gps_wp[wp_number].position.lat;
GPS_WP_longitude = i2c_dataset.gps_wp[wp_number].position.lon;
GPS_WP_altitude = i2c_dataset.gps_wp[wp_number].altitude;
GPS_WP_flags = i2c_dataset.gps_wp[wp_number].flags;
i2c_dataset.status.wp_reached = 0;
} else {
GPS_WP_latitude = GPS_latitude;
GPS_WP_longitude = GPS_longitude;
GPS_WP_altitude = 0;
GPS_WP_flags = 0;
i2c_dataset.status.wp_reached = 1; //With poshold we assume that the wp is reached
}
GPS_calc_longitude_scaling(GPS_WP_latitude);
wp_distance = GPS_distance_cm(GPS_latitude,GPS_longitude,GPS_WP_latitude,GPS_WP_longitude);
target_bearing = GPS_bearing(GPS_latitude,GPS_longitude,GPS_WP_latitude,GPS_WP_longitude);
nav_bearing = target_bearing;
GPS_calc_location_error(GPS_WP_latitude,GPS_WP_longitude,GPS_latitude,GPS_longitude);
original_target_bearing = target_bearing;
waypoint_speed_gov = i2c_dataset.nav_speed_min;
}
////////////////////////////////////////////////////////////////////////////////////
// Calculate a location error between two gps coordinates
// Becuase we are using lat and lon to do our distance errors here's a quick chart:
// 100 = 1m
// 1000 = 11m = 36 feet
// 1800 = 19.80m = 60 feet
// 3000 = 33m
// 10000 = 111m
//
static void GPS_calc_location_error( int32_t target_lat, int32_t target_lng, int32_t gps_lat, int32_t gps_lng )
{
// X Error
long_error = (float)(target_lng - gps_lng) * GPS_scaleLonDown;
// Y Error
lat_error = target_lat - gps_lat;
}
////////////////////////////////////////////////////////////////////////////////////
// Calculate nav_lat and nav_lon from the x and y error and the speed
//
static void GPS_calc_poshold(int x_error, int y_error)
{
int32_t p,i,d;
int32_t output;
int32_t x_target_speed, y_target_speed;
// East / West
x_target_speed = pi_poshold_lon.get_p(x_error); // calculate desired speed from lon error
x_rate_error = x_target_speed - x_actual_speed; // calc the speed error
p = pid_poshold_rate_lon.get_p(x_rate_error);
i = pid_poshold_rate_lon.get_i(x_rate_error + x_error, dTnav);
d = pid_poshold_rate_lon.get_d(x_error, dTnav);
d = constrain(d, -2000, 2000);
// get rid of noise
if ( (i2c_dataset.nav_flags & I2C_NAV_FLAG_LOW_SPEED_D_FILTER) && (abs(x_actual_speed) < 50)) {
d = 0;
}
output = p + i + d;
nav_lon = constrain(output, -NAV_BANK_MAX, NAV_BANK_MAX);
// North / South
y_target_speed = pi_poshold_lat.get_p(y_error); // calculate desired speed from lat error
y_rate_error = y_target_speed - y_actual_speed;
p = pid_poshold_rate_lat.get_p(y_rate_error);
i = pid_poshold_rate_lat.get_i(y_rate_error + y_error, dTnav);
d = pid_poshold_rate_lat.get_d(y_error, dTnav);
d = constrain(d, -2000, 2000);
// get rid of noise
if ( (i2c_dataset.nav_flags & I2C_NAV_FLAG_LOW_SPEED_D_FILTER) && (abs(y_actual_speed) < 50)) {
d = 0;
}
output = p + i + d;
nav_lat = constrain(output, -NAV_BANK_MAX, NAV_BANK_MAX);
// copy over I term to Nav_Rate -- if we change from poshold to RTH this will keep the wind compensation
pid_nav_lon.set_integrator(pid_poshold_rate_lon.get_integrator());
pid_nav_lat.set_integrator(pid_poshold_rate_lat.get_integrator());
}
////////////////////////////////////////////////////////////////////////////////////
// Calculate the desired nav_lat and nav_lon for distance flying such as RTH
//
static void GPS_calc_nav_rate(int max_speed)
{
// push us towards the original track
GPS_update_crosstrack();
// nav_bearing includes crosstrack
float temp = (9000l - nav_bearing) * RADX100;
// East / West
x_rate_error = (cos(temp) * max_speed) - x_actual_speed;
x_rate_error = constrain(x_rate_error, -1000, 1000);
nav_lon = pid_nav_lon.get_pid(x_rate_error, dTnav);
nav_lon = constrain(nav_lon, -NAV_BANK_MAX, NAV_BANK_MAX);
// North / South
y_rate_error = (sin(temp) * max_speed) - y_actual_speed;
y_rate_error = constrain(y_rate_error, -1000, 1000); // added a rate error limit to keep pitching down to a minimum
nav_lat = pid_nav_lat.get_pid(y_rate_error, dTnav);
nav_lat = constrain(nav_lat, -NAV_BANK_MAX, NAV_BANK_MAX);
// copy over I term to poshold_rate - So when arriving and entering to poshold we will have the wind compensation
pid_poshold_rate_lon.set_integrator(pid_nav_lon.get_integrator());
pid_poshold_rate_lat.set_integrator(pid_nav_lat.get_integrator());
}
////////////////////////////////////////////////////////////////////////////////////
// Calculating cross track error, this tries to keep the copter on a direct line
// when flying to a waypoint.
//
static void GPS_update_crosstrack(void)
{
if (abs(wrap_18000(target_bearing - original_target_bearing)) < 4500) { // If we are too far off or too close we don't do track following
float temp = (target_bearing - original_target_bearing) * RADX100;
crosstrack_error = sin(temp) * (wp_distance * (float)((float)i2c_dataset.nav_crosstrack_gain/100.0f)); // Meters we are off track line
nav_bearing = target_bearing + constrain(crosstrack_error, -3000, 3000);
nav_bearing = wrap_36000(nav_bearing);
}else{
nav_bearing = target_bearing;
}
}
////////////////////////////////////////////////////////////////////////////////////
// Determine desired speed when navigating towards a waypoint, also implement slow
// speed rampup when starting a navigation
//
// |< WP Radius
// 0 1 2 3 4 5 6 7 8m
// ...|...|...|...|...|...|...|...|
// 100 | 200 300 400cm/s
// | +|+
// |< we should slow to 1.5 m/s as we hit the target
//
static int16_t GPS_calc_desired_speed(int16_t max_speed, bool _slow)
{
// max_speed is default 400 or 4m/s
if(_slow){
max_speed = min(max_speed, wp_distance / 2);
max_speed = max(max_speed, 0);
}else{
max_speed = min(max_speed, wp_distance);
max_speed = max(max_speed, i2c_dataset.nav_speed_min); // go at least 100cm/s
}
// limit the ramp up of the speed
// waypoint_speed_gov is reset to NAV_MIN_SPEED at each new WP command
if(max_speed > waypoint_speed_gov){
waypoint_speed_gov += (int)(100.0 * dTnav); // increase at .5/ms
max_speed = waypoint_speed_gov;
}
return max_speed;
}
////////////////////////////////////////////////////////////////////////////////////
// Resets all GPS nev parameters and clears up the PID controllers. Prepares for a restarted poshold/navigation
//
void GPS_reset_nav()
{
pi_poshold_lat.reset_I();
pi_poshold_lon.reset_I();
pid_poshold_rate_lon.reset_I();
pid_poshold_rate_lat.reset_I();
pid_nav_lon.reset_I();
pid_nav_lat.reset_I();
nav_lon = 0;
nav_lat = 0;
}
/* The latitude or longitude is coded this way in NMEA frames
dddmm.mmmm coded as degrees + minutes + minute decimal
This function converts this format in a unique unsigned long where 1 degree = 10 000 000
I increased the precision here, even if we think that the gps is not precise enough, with 10e5 precision it has 76cm resolution
with 10e7 it's around 1 cm now. Increasing it further is irrelevant, since even 1cm resolution is unrealistic, however increased
resolution also increased precision of nav calculations
*/
#endif
////////////////////////////////////////////////////////////////////////////////////
// Update i2c_dataset from navigation output
//
void GPS_update_i2c_dataset()
{
i2c_dataset.nav_lat = nav_lat;
i2c_dataset.nav_lon = nav_lon;
i2c_dataset.wp_distance = wp_distance;
i2c_dataset.wp_target_bearing = target_bearing;
i2c_dataset.nav_bearing = nav_bearing;
}
#define DIGIT_TO_VAL(_x) (_x - '0')
uint32_t GPS_coord_to_degrees(char* s)
{
char *p, *q;
uint8_t deg = 0, min = 0;
unsigned int frac_min = 0;
// scan for decimal point or end of field
for (p = s; isdigit(*p); p++)
;
q = s;
// convert degrees
while ((p - q) > 2) {
if (deg)
deg *= 10;
deg += DIGIT_TO_VAL(*q++);
}
// convert minutes
while (p > q) {
if (min)
min *= 10;
min += DIGIT_TO_VAL(*q++);
}
// convert fractional minutes
// expect up to four digits, result is in
// ten-thousandths of a minute
if (*p == '.') {
q = p + 1;
for (int i = 0; i < 4; i++) {
frac_min *= 10;
if (isdigit(*q))
frac_min += *q++ - '0';
}
}
return deg * 10000000UL + (min * 1000000UL + frac_min*100UL) / 6;
}
/* This is am expandable implementation of a GPS frame decoding
This should work with most of modern GPS devices configured to output NMEA frames.
It assumes there are some NMEA GGA, GSA and RMC frames to decode on the serial bus
Using the following data :
GGA
- time
- latitude
- longitude
- GPS fix
- GPS num sat (5 is enough to be +/- reliable)
- GPS alt
GSA
- 3D fix (it could be left out since we have a 3D fix if we have more than 4 sats
RMC
- GPS speed over ground, it will be handy for wind compensation (future)
*/
#define NO_FRAME 0
#define GPGGA_FRAME 1
#define GPGSA_FRAME 2
#define GPRMC_FRAME 3
bool GPS_newFrame(char c) {
uint8_t frameOK = 0;
static uint8_t param = 0, offset = 0, parity = 0;
static char string[15];
static uint8_t checksum_param, gps_frame = NO_FRAME;
switch (c) {
case '$': param = 0; offset = 0; parity = 0;
break;
case ',':
case '*': string[offset] = 0;
if (param == 0) { //frame identification
gps_frame = NO_FRAME;
if (string[0] == 'G' && string[1] == 'P' && string[2] == 'G' && string[3] == 'G' && string[4] == 'A') gps_frame = GPGGA_FRAME;
if (string[0] == 'G' && string[1] == 'P' && string[2] == 'G' && string[3] == 'S' && string[4] == 'A') gps_frame = GPGSA_FRAME;
if (string[0] == 'G' && string[1] == 'P' && string[2] == 'R' && string[3] == 'M' && string[4] == 'C') gps_frame = GPRMC_FRAME;
}
switch (gps_frame)
{
//************* GPGGA FRAME parsing
case GPGGA_FRAME:
switch (param)
{
case 1: i2c_dataset.time = (atof(string)*1000); //up to .000 s precision not needed really but the data is there anyway
break;
//case 2: i2c_dataset.gps_loc.lat = GPS_coord_to_degrees(string);
case 2: GPS_read[LAT] = GPS_coord_to_degrees(string);
break;
//case 3: if (string[0] == 'S') i2c_dataset.gps_loc.lat = -i2c_dataset.gps_loc.lat;
case 3: if (string[0] == 'S') GPS_read[LAT] = -GPS_read[LAT];
break;
//case 4: i2c_dataset.gps_loc.lon = GPS_coord_to_degrees(string);
case 4: GPS_read[LON] = GPS_coord_to_degrees(string);
break;
//case 5: if (string[0] == 'W') i2c_dataset.gps_loc.lon = -i2c_dataset.gps_loc.lon;
case 5: if (string[0] == 'W') GPS_read[LON] = -GPS_read[LON];
break;
case 6: i2c_dataset.status.gps2dfix = string[0] > '0';
break;
case 7: i2c_dataset.status.numsats = atoi(string);
break;
case 9: i2c_dataset.altitude = atoi(string);
break;
}
break;
//************* GPGSA FRAME parsing
case GPGSA_FRAME:
switch (param)
{
case 2: i2c_dataset.status.gps3dfix = string[0] == '3';
break;
}
break;
//************* GPGSA FRAME parsing
case GPRMC_FRAME:
switch(param)
{
case 7: i2c_dataset.ground_speed = (atof(string)*0.5144444)*10; //convert to m/s*100
break;
case 8: i2c_dataset.ground_course = (atof(string)*10); //Convert to degrees *10 (.1 precision)
break;
}
break;
}
param++; offset = 0;
if (c == '*') checksum_param=1;
else parity ^= c;
break;
case '\r':
case '\n':
if (checksum_param) { //parity checksum
uint8_t checksum = 16 * ((string[0]>='A') ? string[0] - 'A'+10: string[0] - '0') + ((string[1]>='A') ? string[1] - 'A'+10: string[1]-'0');
if (checksum == parity) frameOK = 1;
}
checksum_param=0;
break;
default:
if (offset < 15) string[offset++] = c;
if (!checksum_param) parity ^= c;
}
return frameOK && (gps_frame == GPGGA_FRAME);
}
//////////////////////////////////////////////////////////////////////////////////////
// I2C handlers
// Handler for requesting data
//
void requestEvent()
{
if (receivedCommands[0] >= I2C_GPS_GROUND_SPEED) i2c_dataset.status.new_data = 0; //Accessing gps data, switch new_data_flag;
//Write data from the requested data register position
Wire.write((uint8_t *)&i2c_dataset+receivedCommands[0],32); //Write up to 32 byte, since master is responsible for reading and sending NACK
//32 byte limit is in the Wire library, we have to live with it unless writing our own wire library
}
//Handler for receiving data
void receiveEvent(int bytesReceived)
{
uint8_t *ptr;
for (int a = 0; a < bytesReceived; a++) {
if (a < MAX_SENT_BYTES) {
receivedCommands[a] = Wire.read();
} else {
Wire.read(); // if we receive more data then allowed just throw it away
}
}
if (receivedCommands[0] == I2C_GPS_COMMAND) { new_command = receivedCommands[1]; return; } //Just one byte, ignore all others
if(bytesReceived == 1 && (receivedCommands[0] < REG_MAP_SIZE)) { return; } //read command from a given register
if(bytesReceived == 1 && (receivedCommands[0] >= REG_MAP_SIZE)){ //Addressing over the reg_map fallback to first byte
receivedCommands[0] = 0x00;
return;
}
//More than 1 byte was received, so there is definitely some data to write into a register
//Check for writeable registers and discard data is it's not writeable
if ((receivedCommands[0]>=I2C_GPS_CROSSTRACK_GAIN) && (receivedCommands[0]<=REG_MAP_SIZE)) { //Writeable registers above I2C_GPS_WP0
ptr = (uint8_t *)&i2c_dataset+receivedCommands[0];
for (int a = 1; a < bytesReceived; a++) { *ptr++ = receivedCommands[a]; }
}
}
#if !defined(RUSHDUINO_GPS)
void blink_update()
{
uint32_t now = millis();
if(_statusled_timer < now) {
if(lastframe_time+5000 < now) {
// no gps communication
_statusled_state = !_statusled_state;
digitalWrite(ledPin, _statusled_state ? HIGH : LOW); // set the LED off
_statusled_timer = now + 1000;
return;
}
if(_statusled_blinks==0) {
if(i2c_dataset.status.gps3dfix == 1)
_statusled_blinks=3;
else if(i2c_dataset.status.gps2dfix == 1)
_statusled_blinks=2;
else
_statusled_blinks=1;
}
if(_statusled_state) {
_statusled_blinks--;
_statusled_state = false;
_statusled_timer = now + ((_statusled_blinks>0) ? BLINK_INTERVAL : 1000);
digitalWrite(ledPin, LOW); // set the LED off
} else {
_statusled_state = true;
_statusled_timer = now + BLINK_INTERVAL;
digitalWrite(ledPin, HIGH); // set the LED on
}
}
}
#endif
/////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
// Setup
//
void setup() {
uint8_t i;
Serial.begin(115200);
#if defined(DEBUG_SERIAL)
Serial.print("enter setup\r\n");
delay(100);
#endif
pinMode(ledPin, OUTPUT);
pinMode(10, OUTPUT);
digitalWrite(10,HIGH);
delay(100);
#if defined(GPS_PROMINI_SERIAL) || defined(GPS_I2C_WITH_SD)
// see if the card is present and can be initialized:
SDPresent = SD.begin(chipSelect);
if (!SDPresent){
#if defined(DEBUG_SERIAL)
Serial.println("Card failed, or not present");
delay(100);
#endif
}
else{
#if defined(DEBUG_SERIAL)
Serial.println("Card successfully opened");
delay(100);
#endif
// i = CountFileInDirectory();
// i--;
i = 0;
do{
dataString = "GPSLog" + String(i++,DEC) + ".kml";
dataString.toCharArray(FileName, 15);
}while(SD.exists(FileName));
// do
// {
// i++;
// if (i >= 100)
// {
// i = 0;
// FileName = "GPSLog0.kml";
// SD.remove(FileName);
// }
// dataString = "GPSLog" + String(i,DEC);
// dataString += ".kml";
// dataString.toCharArray(FileName, 15);
// }
// while(SD.exists(FileName));
dataFile = SD.open(FileName, FILE_WRITE);
#if defined(DEBUG_SERIAL)
Serial.println("File opened?");
//Serial.println("FileName: "+ dataString);
delay(100);
#endif
Serial.println("FileName: "+ dataString);
//******* KML xml File header for Google Earth *****//
if (!dataFile){
#if defined(DEBUG_SERIAL)
Serial.println("File could not be opened");
delay(100);
#endif
}
else{
#if defined(DEBUG_SERIAL)
Serial.println("File successfully opened");
#endif
for (i = 0; i < STRINGTABLELENGTH; i++)
{
strcpy_P(testbuffer, (char*)pgm_read_word(&(string_table[i]))); // Necessary casts and dereferencing, just copy.
dataFile.println(testbuffer);
}
// dataString = "<kml>"; dataFile.println(dataString);
// dataString = "<kml xmlns:gx=";
// dataString += '"';
// dataString += "http:/";
// dataString += "/www.opengis.net/kml/2.2";
// dataString += '"';
// dataString += ">"; dataFile.println(dataString);
//
// dataString = "<Placemark>"; dataFile.println(dataString);
// dataString = " <name>Rushduino GPS Logger</name>"; dataFile.println(dataString);
// dataString = " <LineString>"; dataFile.println(dataString);
// dataString = " <extrude>1</extrude>"; dataFile.println(dataString);
// dataString = " <gx:altitudeMode>relativeToSeaFloor</gx:altitudeMode>"; dataFile.println(dataString);
// dataString = " <coordinates>"; dataFile.println(dataString);
EndCoordinateLine = dataFile.position(); // Line Position of start of coodinates
dataFile.flush();
delay(200);
LedState = LOW; digitalWrite(ledPin, LedState);
}
}
//Serial.print("$PMTK314,-1*04\r\n"); // factory reset
Serial.print("$PMTK314,0,1,0,1,1,0,0,0,0,0,0,0,0,0,0,0,0*29\r\n");
LedState = HIGH;
digitalWrite(ledPin, LedState);
#endif
#if !defined (GPS_PROMINI_SERIAL)
//Init i2c_dataset;
uint8_t *ptr = (uint8_t *)&i2c_dataset;
for (i=0;i<sizeof(i2c_dataset);i++) { *ptr = 0; ptr++;}
//Set up default parameters
i2c_dataset.sw_version = VERSION;
i2c_dataset.nav_crosstrack_gain = 100; // Crosstrack gain = 1
i2c_dataset.nav_speed_min = 100; // cm/s
i2c_dataset.nav_speed_max = 400; // cm/s
i2c_dataset.nav_bank_max = 3000; // 30deg
i2c_dataset.wp_radius = 200; //cm -> 2m
i2c_dataset.poshold_p = POSHOLD_P * 100;
i2c_dataset.poshold_i = POSHOLD_I * 100;
i2c_dataset.poshold_imax = POSHOLD_IMAX;
i2c_dataset.poshold_rate_p = POSHOLD_RATE_P * 10;
i2c_dataset.poshold_rate_i = POSHOLD_RATE_I * 100;
i2c_dataset.poshold_rate_d = POSHOLD_RATE_D * 1000;
i2c_dataset.poshold_rate_imax = POSHOLD_RATE_IMAX;
i2c_dataset.nav_p = NAV_P * 10;
i2c_dataset.nav_i = NAV_I * 100;
i2c_dataset.nav_d = NAV_D * 1000;
i2c_dataset.nav_imax = NAV_IMAX;
i2c_dataset.nav_flags = 0x80 + 0x40; // GPS filter and low speed filters are on
//Start I2C communication routines
Wire.begin(I2C_ADDRESS); // DO NOT FORGET TO COMPILE WITH 400KHz!!! else change TWBR Speed to 100khz on Host !!! Address 0x40 write 0x41 read
Wire.onRequest(requestEvent); // Set up event handlers
Wire.onReceive(receiveEvent);
#endif
}
/******************************************************************************************************************/
/******************************************************* Main loop ************************************************/
/******************************************************************************************************************/
void loop() {
static uint8_t GPS_fix_home;
static uint8_t _command_wp;
static uint8_t _command;
static uint32_t _watchdog_timer = 0;
static uint32_t SD_Timer = 0;
uint8_t axis;
uint16_t fraction3[2];
while (Serial.available()) {
if (GPS_newFrame(Serial.read())) {
// We have a valid GGA frame and we have lat and lon in GPS_read_lat and GPS_read_lon, apply moving average filter
// this is a little bit tricky since the 1e7/deg precision easily overflow a long, so we apply the filter to the fractions
// only, and strip the full degrees part. This means that we have to disable the filter if we are very close to a degree line
#if defined (GPS_I2C_WITHOUT_SD)
if (i2c_dataset.nav_flags & I2C_NAV_FLAG_GPS_FILTER) { //is filtering switched on ?
GPS_filter_index = ++GPS_filter_index % GPS_FILTER_VECTOR_LENGTH;
for (axis = 0; axis< 2; axis++) {
GPS_degree[axis] = GPS_read[axis] / 10000000; // get the degree to assure the sum fits to the int32_t
// How close we are to a degree line ? its the first three digits from the fractions of degree
//Check if we are close to a degree line, if yes, disable averaging,
fraction3[axis] = (GPS_read[axis]- GPS_degree[axis]*10000000) / 10000;
GPS_filter_sum[axis] -= GPS_filter[axis][GPS_filter_index];
GPS_filter[axis][GPS_filter_index] = GPS_read[axis] - (GPS_degree[axis]*10000000);
GPS_filter_sum[axis] += GPS_filter[axis][GPS_filter_index];
GPS_filtered[axis] = GPS_filter_sum[axis] / GPS_FILTER_VECTOR_LENGTH + (GPS_degree[axis]*10000000);
}
if ( nav_mode == NAV_MODE_POSHOLD) { //we use gps averaging only in poshold mode...
if ( fraction3[LAT]>1 && fraction3[LAT]<999 ) i2c_dataset.gps_loc.lat = GPS_filtered[LAT]; else i2c_dataset.gps_loc.lat = GPS_read[LAT];
if ( fraction3[LON]>1 && fraction3[LON]<999 ) i2c_dataset.gps_loc.lon = GPS_filtered[LON]; else i2c_dataset.gps_loc.lon = GPS_read[LON];
} else {
i2c_dataset.gps_loc.lat = GPS_read[LAT];
i2c_dataset.gps_loc.lon = GPS_read[LON];
}
} else { // ignore filtering since it switced off in the nav_flags
i2c_dataset.gps_loc.lat = GPS_read[LAT];
i2c_dataset.gps_loc.lon = GPS_read[LON];
}
#endif
// GPS_latitude = 471234567;
// GPS_longitude = 477654321;
// RecordToSD();
// numsa >=5
if (i2c_dataset.status.gps3dfix == 1 && i2c_dataset.status.numsats >= 2) {
Serial.print("gut! \r\n");
lastframe_time = millis();
//copy the gps coordinates to variables used for calculations
// GPS_latitude = i2c_dataset.gps_loc.lat;
// GPS_longitude = i2c_dataset.gps_loc.lon;
GPS_latitude = GPS_read[LON];
GPS_longitude = GPS_read[LAT];
#if defined(GPS_PROMINI_SERIAL) || defined(GPS_I2C_WITH_SD) && defined(RUSHDUINO_GPS)
if(SD_Timer + 1000 < millis()){
RecordToSD();
SD_Timer = millis();
}
#endif
// It's just for safety since home position must be set from the host
if (GPS_fix_home == 0) {
GPS_fix_home = 1;
i2c_dataset.gps_wp[0].position.lat = GPS_latitude;
i2c_dataset.gps_wp[0].position.lon = GPS_longitude;
GPS_calc_longitude_scaling(GPS_latitude); //need an initial value for distance and bearing calc
}
//dTnav calculation
//Time for calculating x,y speed and navigation pids
dTnav = (float)(millis() - nav_loopTimer)/ 1000.0;
nav_loopTimer = millis();
// prevent runup from bad GPS
dTnav = min(dTnav, 1.0);
_watchdog_timer = millis(); //Reset watchdog timer
//calculate distance and bearings for gui and other stuff continously this is independent from navigation
i2c_dataset.distance_to_home = GPS_distance_cm(GPS_latitude,GPS_longitude,i2c_dataset.gps_wp[0].position.lat,i2c_dataset.gps_wp[0].position.lon);
i2c_dataset.home_to_copter_bearing = GPS_bearing(i2c_dataset.gps_wp[0].position.lat,i2c_dataset.gps_wp[0].position.lon,GPS_latitude,GPS_longitude);
//calculate the current velocity based on gps coordinates continously to get a valid speed at the moment when we start navigating
GPS_calc_velocity(GPS_latitude,GPS_longitude);
#if defined(GPS_I2C_WITHOUT_SD)
if (GPSMode != 0){ //ok we are navigating
//do gps nav calculations here
wp_distance = GPS_distance_cm(GPS_latitude,GPS_longitude,GPS_WP_latitude,GPS_WP_longitude);
target_bearing = GPS_bearing(GPS_latitude,GPS_longitude,GPS_WP_latitude,GPS_WP_longitude);
//GPS_calc_velocity(GPS_latitude,GPS_longitude);
GPS_calc_location_error(GPS_WP_latitude,GPS_WP_longitude,GPS_latitude,GPS_longitude);
switch (nav_mode) {
case NAV_MODE_POSHOLD:
//Desired output is in nav_lat and nav_lon where 1deg inclination is 100
GPS_calc_poshold(long_error, lat_error);
break;
case NAV_MODE_WP:
int16_t speed = GPS_calc_desired_speed(i2c_dataset.nav_speed_max, true); //slow navigation
// use error as the desired rate towards the target
GPS_calc_nav_rate(speed);
// Are we there yet ?(within 2 meters of the destination)
if ((wp_distance <= i2c_dataset.wp_radius) || check_missed_wp()){ //if yes switch to poshold mode
nav_mode = NAV_MODE_POSHOLD;
//set reached flag
i2c_dataset.status.wp_reached = 1;
}
break;
} //switch nav mode
} // if GPSmode!=0
#endif
// update i2c dataset from nav
GPS_update_i2c_dataset();
} else { // we does not have 3d fix or numsats less than 5 , stop navigation
nav_lat = 0;
nav_lon = 0;
GPSMode = GPSMODE_NONAV;
nav_mode = NAV_MODE_NONE;
wp_distance = 0;
i2c_dataset.distance_to_home = 0;
i2c_dataset.home_to_copter_bearing = 0;
GPS_update_i2c_dataset();
}
// have new data at this point anyway
i2c_dataset.status.new_data = 1;
} // new frame
} //while
#if !defined(RUSHDUINO_GPS)
blink_update();
#endif
//check watchdog timer, after 1200ms without valid packet, assume that gps communication is lost.
if (_watchdog_timer != 0)
{
if (_watchdog_timer+1200 < millis())
{
i2c_dataset.status.gps2dfix = 0;
i2c_dataset.status.gps3dfix = 0;
i2c_dataset.status.numsats = 0;
i2c_dataset.gps_loc.lat = 0;
i2c_dataset.gps_loc.lon = 0;
nav_lat = 0;
nav_lon = 0;
GPS_update_i2c_dataset();
_watchdog_timer = 0;
i2c_dataset.status.new_data = 1;
}
}
#if defined(GPS_I2C_WITHOUT_SD)
//Check for new incoming command on I2C
if (new_command!=0) {
_command = new_command; //save command byte for processing
new_command = 0; //clear it
_command_wp = (_command & 0xF0) >> 4; //mask 4 MSB bits and shift down
_command = _command & 0x0F; //empty 4MSB bits
switch (_command) {
case I2C_GPS_COMMAND_POSHOLD:
GPS_set_next_wp(16); //wp16 is a virtual one, means current location
GPSMode = GPSMODE_HOLD;
nav_mode = NAV_MODE_POSHOLD;
i2c_dataset.status.new_data = 0; //invalidate current dataset
break;
case I2C_GPS_COMMAND_START_NAV:
GPS_set_next_wp(_command_wp);
GPSMode = GPSMODE_WP;
nav_mode = NAV_MODE_WP;
i2c_dataset.status.new_data = 0; //invalidate current dataset
break;
case I2C_GPS_COMMAND_SET_WP:
i2c_dataset.gps_wp[_command_wp].position.lat = GPS_latitude;
i2c_dataset.gps_wp[_command_wp].position.lon = GPS_longitude;
break;
case I2C_GPS_COMMAND_UPDATE_PIDS:
pi_poshold_lat.kP((float)i2c_dataset.poshold_p/100.0f);
pi_poshold_lon.kP((float)i2c_dataset.poshold_p/100.0f);
pi_poshold_lat.kI((float)i2c_dataset.poshold_i/100.0f);
pi_poshold_lon.kI((float)i2c_dataset.poshold_i/100.0f);
pi_poshold_lat.imax(i2c_dataset.poshold_imax*100);
pi_poshold_lon.imax(i2c_dataset.poshold_imax*100);
pid_poshold_rate_lat.kP((float)i2c_dataset.poshold_rate_p/10.0f);
pid_poshold_rate_lon.kP((float)i2c_dataset.poshold_rate_p/10.0f);
pid_poshold_rate_lat.kI((float)i2c_dataset.poshold_rate_i/100.0f);
pid_poshold_rate_lon.kI((float)i2c_dataset.poshold_rate_i/100.0f);
pid_poshold_rate_lat.kD((float)i2c_dataset.poshold_rate_d/1000.0f);
pid_poshold_rate_lon.kD((float)i2c_dataset.poshold_rate_d/1000.0f);
pid_poshold_rate_lat.imax(i2c_dataset.poshold_rate_imax*100);
pid_poshold_rate_lon.imax(i2c_dataset.poshold_rate_imax*100);
pid_nav_lat.kP((float)i2c_dataset.nav_p/10.0f);
pid_nav_lon.kP((float)i2c_dataset.nav_p/10.0f);
pid_nav_lat.kI((float)i2c_dataset.nav_i/100.0f);
pid_nav_lon.kI((float)i2c_dataset.nav_i/100.0f);
pid_nav_lat.kD((float)i2c_dataset.nav_d/1000.0f);
pid_nav_lon.kD((float)i2c_dataset.nav_d/1000.0f);
pid_nav_lat.imax(i2c_dataset.nav_imax*100);
pid_nav_lon.imax(i2c_dataset.nav_imax*100);
break;
case I2C_GPS_COMMAND_STOP_NAV:
GPS_reset_nav();
GPSMode = GPSMODE_NONAV;
nav_mode = NAV_MODE_NONE;
GPS_update_i2c_dataset();
i2c_dataset.status.new_data = 1;
break;
} //switch
}
#endif
}
#if defined (GPS_PROMINI_SERIAL) || defined(GPS_I2C_WITH_SD)
uint8_t ConvertDegres(long Datas)
{
return uint8_t(Datas / 10000000);
}
uint16_t ConvertMinute(long Datas, uint8_t DatasD)
{
return uint16_t(Datas - (DatasD * 10000000));
}
void RecordToSD()
{
if (SDPresent){
// uint8_t Degres=0;
// uint16_t Minutes=0;
//dataFile = SD.open(FileName, FILE_WRITE);
if (dataFile) {
Serial.print("datafile present\r\n");
//******* Latitude *****//
//Degres = int(i2c_dataset.gps_loc.lat / 100000);
//Minutes = long(i2c_dataset.gps_loc.lat - (Degres * 100000));
// Degres = ConvertDegres(GPS_latitude);
// Minutes = ConvertMinute(GPS_latitude,Degres);
// Serial.println("Lat: Deg: " + String(Degres) + "Min: " + String(Minutes));
//
// dataString = String(Degres);
// dataString += '.';
// dataString += String(abs(Minutes));
// dataString += ',';
tmpString = String(GPS_latitude);
int length = tmpString.length() ;
if(length == 8){
dataString = tmpString.substring(0, 1);
dataString += ".";
dataString += tmpString.substring(1, 8);
}
if(length == 9){
dataString = tmpString.substring(0, 2);
dataString += ".";
dataString += tmpString.substring(2, 9);
}
dataString += ',';
//******* Longitude *****//
//Degres = uint8_t(i2c_dataset.gps_loc.lon / 100000);
//Minutes = uint16_t(i2c_dataset.gps_loc.lon - (Degres * 100000));
// Degres = ConvertDegres(GPS_longitude);
// Minutes = ConvertMinute(GPS_longitude,Degres);
// Serial.println("Long: Deg: " + String(Degres) + "Min: " + String(Minutes));
// dataString += String(Degres);
// dataString += '.';
// dataString += String(abs(Minutes));
// dataString += ',';
tmpString = String(GPS_longitude);
length = tmpString.length() ;
if(length == 8){
dataString += tmpString.substring(0, 1);
dataString += ".";
dataString += tmpString.substring(1, 8);
}
if(length == 9){
dataString += tmpString.substring(0, 2);
dataString += ".";
dataString += tmpString.substring(2, 9);
}
dataString += ',';
//******* Altitude *****//
dataString += String(i2c_dataset.altitude);
//dataString += String(Degres)+'.'+String(abs(Minutes))+','+String(i2c_dataset.altitude);
//******* Record to file *****//
dataFile.seek(EndCoordinateLine); // Put cursor to the last line of recorded position
dataFile.println(dataString);
//dataFile.println("EndCoordinateLine: " + String(EndCoordinateLine));
EndCoordinateLine = dataFile.position(); // Memory the new last line of recorded position
//******* KML xml File footer for Google Earth *****//
dataString = "</coordinates>"; dataFile.println(dataString);
dataString = "</LineString>"; dataFile.println(dataString);
dataString = "</Placemark>"; dataFile.println(dataString);
dataString = "</Document>"; dataFile.println(dataString);
dataString = "</kml>"; dataFile.println(dataString);
//dataString = "</coordinates>/r/n</LineString>/r/n</Placemark>/r/n</kml>"; dataFile.println(dataString);
dataFile.flush();
//dataFile.close();
Serial.println(String(EndCoordinateLine));
if (LedState == LOW) LedState = HIGH; else LedState = LOW; digitalWrite(ledPin, LedState);
}
}
}
uint8_t CountFileInDirectory()
{
uint8_t Counter = 0;
//File dataFile;
dataFile = SD.open("/");
while(true)
{
File entry = dataFile.openNextFile();
if (!entry)
{
dataFile.close();
break; // no more files
}
if (!entry.isDirectory()) Counter++;
}
dataFile.close();
return Counter;
}
#endif

 
Keine Kommentare:
Kommentar veröffentlichen