mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
lots of minor changes, Logs should be working better now.
Pos hold is now called "Loiter" - I don't want to have a flight mode called HOLD POS... git-svn-id: https://arducopter.googlecode.com/svn/trunk@1759 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
7f330fbb6c
commit
8114b717f2
@ -189,10 +189,8 @@ const char* flight_mode_strings[] = {
|
|||||||
"FBW",
|
"FBW",
|
||||||
"AUTO",
|
"AUTO",
|
||||||
"GCS_AUTO",
|
"GCS_AUTO",
|
||||||
"POS_HOLD",
|
"LOITER",
|
||||||
"RTL",
|
"RTL"};
|
||||||
"TAKEOFF",
|
|
||||||
"LAND"};
|
|
||||||
|
|
||||||
/* Radio values
|
/* Radio values
|
||||||
Channel assignments
|
Channel assignments
|
||||||
@ -304,6 +302,9 @@ boolean land_complete;
|
|||||||
int landing_distance; // meters;
|
int landing_distance; // meters;
|
||||||
long old_alt; // used for managing altitude rates
|
long old_alt; // used for managing altitude rates
|
||||||
int velocity_land;
|
int velocity_land;
|
||||||
|
bool nav_yaw_towards_wp; // point at the next WP
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// Loiter management
|
// Loiter management
|
||||||
// -----------------
|
// -----------------
|
||||||
@ -363,7 +364,7 @@ struct Location next_WP; // next waypoint
|
|||||||
struct Location tell_command; // command for telemetry
|
struct Location tell_command; // command for telemetry
|
||||||
struct Location next_command; // command preloaded
|
struct Location next_command; // command preloaded
|
||||||
long target_altitude; // used for
|
long target_altitude; // used for
|
||||||
long offset_altitude; // used for
|
//long offset_altitude; // used for
|
||||||
boolean home_is_set; // Flag for if we have g_gps lock and have set the home location
|
boolean home_is_set; // Flag for if we have g_gps lock and have set the home location
|
||||||
|
|
||||||
|
|
||||||
@ -415,6 +416,8 @@ float load; // % MCU cycles used
|
|||||||
|
|
||||||
byte counter_one_herz;
|
byte counter_one_herz;
|
||||||
|
|
||||||
|
byte GPS_failure_counter = 255;
|
||||||
|
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
// Top-level logic
|
// Top-level logic
|
||||||
////////////////////////////////////////////////////////////////////////////////
|
////////////////////////////////////////////////////////////////////////////////
|
||||||
@ -506,7 +509,10 @@ void medium_loop()
|
|||||||
//-------------------------------
|
//-------------------------------
|
||||||
case 0:
|
case 0:
|
||||||
medium_loopCounter++;
|
medium_loopCounter++;
|
||||||
|
|
||||||
|
if(GPS_failure_counter > 0){
|
||||||
update_GPS();
|
update_GPS();
|
||||||
|
}
|
||||||
//readCommands();
|
//readCommands();
|
||||||
|
|
||||||
if(g.compass_enabled){
|
if(g.compass_enabled){
|
||||||
@ -678,11 +684,8 @@ void slow_loop()
|
|||||||
// between 1 and 5 Hz
|
// between 1 and 5 Hz
|
||||||
#else
|
#else
|
||||||
gcs.send_message(MSG_LOCATION);
|
gcs.send_message(MSG_LOCATION);
|
||||||
// XXX
|
|
||||||
// gcs.send_message(MSG_CPU_LOAD, load*100);
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
gcs.send_message(MSG_HEARTBEAT); // XXX This is running at 3 1/3 Hz instead of 1 Hz
|
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -693,10 +696,15 @@ void slow_loop()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// 1Hz loop
|
||||||
void super_slow_loop()
|
void super_slow_loop()
|
||||||
{
|
{
|
||||||
if (g.log_bitmask & MASK_LOG_CUR)
|
if (g.log_bitmask & MASK_LOG_CUR)
|
||||||
Log_Write_Current();
|
Log_Write_Current();
|
||||||
|
|
||||||
|
gcs.send_message(MSG_HEARTBEAT); // XXX This is running at 3 1/3 Hz instead of 1 Hz
|
||||||
|
// gcs.send_message(MSG_CPU_LOAD, load*100);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void update_GPS(void)
|
void update_GPS(void)
|
||||||
@ -705,6 +713,8 @@ void update_GPS(void)
|
|||||||
update_GPS_light();
|
update_GPS_light();
|
||||||
|
|
||||||
if (g_gps->new_data && g_gps->fix) {
|
if (g_gps->new_data && g_gps->fix) {
|
||||||
|
GPS_failure_counter = 255;
|
||||||
|
|
||||||
// XXX We should be sending GPS data off one of the regular loops so that we send
|
// XXX We should be sending GPS data off one of the regular loops so that we send
|
||||||
// no-GPS-fix data too
|
// no-GPS-fix data too
|
||||||
#if GCS_PROTOCOL != GCS_PROTOCOL_MAVLINK
|
#if GCS_PROTOCOL != GCS_PROTOCOL_MAVLINK
|
||||||
@ -746,6 +756,9 @@ void update_GPS(void)
|
|||||||
current_loc.lng = g_gps->longitude; // Lon * 10 * *7
|
current_loc.lng = g_gps->longitude; // Lon * 10 * *7
|
||||||
current_loc.lat = g_gps->latitude; // Lat * 10 * *7
|
current_loc.lat = g_gps->latitude; // Lat * 10 * *7
|
||||||
|
|
||||||
|
}else{
|
||||||
|
if(GPS_failure_counter > 0)
|
||||||
|
GPS_failure_counter--;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -928,7 +941,7 @@ void update_current_flight_mode(void)
|
|||||||
output_stabilize_pitch();
|
output_stabilize_pitch();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case POSITION_HOLD:
|
case LOITER:
|
||||||
|
|
||||||
// Yaw control
|
// Yaw control
|
||||||
// -----------
|
// -----------
|
||||||
@ -1047,7 +1060,10 @@ void update_alt()
|
|||||||
|
|
||||||
// altitude smoothing
|
// altitude smoothing
|
||||||
// ------------------
|
// ------------------
|
||||||
calc_altitude_error();
|
calc_altitude_smoothing_error();
|
||||||
|
|
||||||
|
|
||||||
|
//calc_altitude_error();
|
||||||
|
|
||||||
// Amount of throttle to apply for hovering
|
// Amount of throttle to apply for hovering
|
||||||
// ----------------------------------------
|
// ----------------------------------------
|
||||||
|
@ -231,7 +231,7 @@ void calc_nav_throttle()
|
|||||||
float scaler = 1.0;
|
float scaler = 1.0;
|
||||||
|
|
||||||
if(error < 0){
|
if(error < 0){
|
||||||
scaler = (altitude_sensor == BARO) ? .5 : .9;
|
scaler = (altitude_sensor == BARO) ? .5 : .8;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(altitude_sensor == BARO){
|
if(altitude_sensor == BARO){
|
||||||
@ -276,7 +276,7 @@ void output_manual_yaw()
|
|||||||
|
|
||||||
void auto_yaw()
|
void auto_yaw()
|
||||||
{
|
{
|
||||||
if(next_WP.options & WP_OPT_YAW){
|
if(nav_yaw_towards_wp){
|
||||||
nav_yaw = target_bearing;
|
nav_yaw = target_bearing;
|
||||||
}
|
}
|
||||||
output_yaw_with_hold(true); // hold yaw
|
output_yaw_with_hold(true); // hold yaw
|
||||||
|
@ -201,7 +201,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
{
|
{
|
||||||
|
|
||||||
case MAV_ACTION_LAUNCH:
|
case MAV_ACTION_LAUNCH:
|
||||||
set_mode(TAKEOFF);
|
//set_mode(TAKEOFF);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_ACTION_RETURN:
|
case MAV_ACTION_RETURN:
|
||||||
@ -209,7 +209,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_ACTION_EMCY_LAND:
|
case MAV_ACTION_EMCY_LAND:
|
||||||
set_mode(LAND);
|
//set_mode(LAND);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_ACTION_HALT:
|
case MAV_ACTION_HALT:
|
||||||
@ -263,7 +263,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
case MAV_ACTION_REC_STOP: break;
|
case MAV_ACTION_REC_STOP: break;
|
||||||
|
|
||||||
case MAV_ACTION_TAKEOFF:
|
case MAV_ACTION_TAKEOFF:
|
||||||
set_mode(TAKEOFF);
|
//set_mode(TAKEOFF);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_ACTION_NAVIGATE:
|
case MAV_ACTION_NAVIGATE:
|
||||||
@ -271,7 +271,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_ACTION_LAND:
|
case MAV_ACTION_LAND:
|
||||||
set_mode(LAND);
|
//set_mode(LAND);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MAV_ACTION_LOITER:
|
case MAV_ACTION_LOITER:
|
||||||
|
@ -59,7 +59,7 @@ print_log_menu(void)
|
|||||||
// Pass it the capitalised name of the log option, as defined
|
// Pass it the capitalised name of the log option, as defined
|
||||||
// in defines.h but without the LOG_ prefix. It will check for
|
// in defines.h but without the LOG_ prefix. It will check for
|
||||||
// the bit being set and print the name of the log option to suit.
|
// the bit being set and print the name of the log option to suit.
|
||||||
#define PLOG(_s) if (g.log_bitmask & LOGBIT_ ## _s) Serial.printf_P(PSTR(" %S"), PSTR(#_s))
|
#define PLOG(_s) if (g.log_bitmask & MASK_LOG_ ## _s) Serial.printf_P(PSTR(" %S"), PSTR(#_s))
|
||||||
PLOG(ATTITUDE_FAST);
|
PLOG(ATTITUDE_FAST);
|
||||||
PLOG(ATTITUDE_MED);
|
PLOG(ATTITUDE_MED);
|
||||||
PLOG(GPS);
|
PLOG(GPS);
|
||||||
@ -69,7 +69,7 @@ print_log_menu(void)
|
|||||||
PLOG(MODE);
|
PLOG(MODE);
|
||||||
PLOG(RAW);
|
PLOG(RAW);
|
||||||
PLOG(CMD);
|
PLOG(CMD);
|
||||||
PLOG(CURRENT);
|
PLOG(CUR);
|
||||||
#undef PLOG
|
#undef PLOG
|
||||||
}
|
}
|
||||||
Serial.println();
|
Serial.println();
|
||||||
@ -107,7 +107,10 @@ dump_log(uint8_t argc, const Menu::arg *argv)
|
|||||||
|
|
||||||
get_log_boundaries(last_log_num, dump_log, dump_log_start, dump_log_end);
|
get_log_boundaries(last_log_num, dump_log, dump_log_start, dump_log_end);
|
||||||
Serial.printf_P(PSTR("Dumping Log number %d, start page %d, end page %d\n"),
|
Serial.printf_P(PSTR("Dumping Log number %d, start page %d, end page %d\n"),
|
||||||
dump_log, dump_log_start, dump_log_end);
|
dump_log,
|
||||||
|
dump_log_start,
|
||||||
|
dump_log_end);
|
||||||
|
|
||||||
Log_Read(dump_log_start, dump_log_end);
|
Log_Read(dump_log_start, dump_log_end);
|
||||||
Serial.printf_P(PSTR("Log read complete\n"));
|
Serial.printf_P(PSTR("Log read complete\n"));
|
||||||
}
|
}
|
||||||
@ -128,6 +131,7 @@ erase_logs(uint8_t argc, const Menu::arg *argv)
|
|||||||
DataFlash.WriteByte(LOG_INDEX_MSG);
|
DataFlash.WriteByte(LOG_INDEX_MSG);
|
||||||
DataFlash.WriteByte(0);
|
DataFlash.WriteByte(0);
|
||||||
DataFlash.WriteByte(END_BYTE);
|
DataFlash.WriteByte(END_BYTE);
|
||||||
|
DataFlash.FinishWrite();
|
||||||
Serial.printf_P(PSTR("\nLog erased.\n"));
|
Serial.printf_P(PSTR("\nLog erased.\n"));
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -152,7 +156,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
|
|||||||
if (!strcasecmp_P(argv[1].str, PSTR("all"))) {
|
if (!strcasecmp_P(argv[1].str, PSTR("all"))) {
|
||||||
bits = ~(bits = 0);
|
bits = ~(bits = 0);
|
||||||
} else {
|
} else {
|
||||||
#define TARG(_s) if (!strcasecmp_P(argv[1].str, PSTR(#_s))) bits |= LOGBIT_ ## _s
|
#define TARG(_s) if (!strcasecmp_P(argv[1].str, PSTR(#_s))) bits |= MASK_LOG_ ## _s
|
||||||
TARG(ATTITUDE_FAST);
|
TARG(ATTITUDE_FAST);
|
||||||
TARG(ATTITUDE_MED);
|
TARG(ATTITUDE_MED);
|
||||||
TARG(GPS);
|
TARG(GPS);
|
||||||
@ -162,7 +166,7 @@ select_logs(uint8_t argc, const Menu::arg *argv)
|
|||||||
TARG(MODE);
|
TARG(MODE);
|
||||||
TARG(RAW);
|
TARG(RAW);
|
||||||
TARG(CMD);
|
TARG(CMD);
|
||||||
TARG(CURRENT);
|
TARG(CUR);
|
||||||
#undef TARG
|
#undef TARG
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -373,7 +377,7 @@ void Log_Write_Startup(byte type)
|
|||||||
struct Location cmd = get_wp_with_index(0);
|
struct Location cmd = get_wp_with_index(0);
|
||||||
Log_Write_Cmd(0, &cmd);
|
Log_Write_Cmd(0, &cmd);
|
||||||
|
|
||||||
for (int i=1; i<g.waypoint_total; i++){
|
for (int i = 1; i <= g.waypoint_total; i++){
|
||||||
cmd = get_wp_with_index(i);
|
cmd = get_wp_with_index(i);
|
||||||
Log_Write_Cmd(i, &cmd);
|
Log_Write_Cmd(i, &cmd);
|
||||||
}
|
}
|
||||||
@ -486,7 +490,7 @@ void Log_Write_Current()
|
|||||||
// Read a Current packet
|
// Read a Current packet
|
||||||
void Log_Read_Current()
|
void Log_Read_Current()
|
||||||
{
|
{
|
||||||
Serial.printf("CURR: %d, %4.4f, %4.4f, %d\n",
|
Serial.printf_P(PSTR("CURR: %d, %4.4f, %4.4f, %d\n"),
|
||||||
DataFlash.ReadInt(),
|
DataFlash.ReadInt(),
|
||||||
((float)DataFlash.ReadInt() / 100.f),
|
((float)DataFlash.ReadInt() / 100.f),
|
||||||
((float)DataFlash.ReadInt() / 100.f),
|
((float)DataFlash.ReadInt() / 100.f),
|
||||||
@ -498,7 +502,7 @@ void Log_Read_Control_Tuning()
|
|||||||
{
|
{
|
||||||
float logvar;
|
float logvar;
|
||||||
|
|
||||||
Serial.print("CTUN:");
|
Serial.printf_P(PSTR("CTUN:"));
|
||||||
for (int y = 1; y < 10; y++) {
|
for (int y = 1; y < 10; y++) {
|
||||||
logvar = DataFlash.ReadInt();
|
logvar = DataFlash.ReadInt();
|
||||||
if(y < 8) logvar = logvar/100.f;
|
if(y < 8) logvar = logvar/100.f;
|
||||||
@ -512,21 +516,14 @@ void Log_Read_Control_Tuning()
|
|||||||
// Read a nav tuning packet
|
// Read a nav tuning packet
|
||||||
void Log_Read_Nav_Tuning()
|
void Log_Read_Nav_Tuning()
|
||||||
{
|
{
|
||||||
Serial.print("NTUN:");
|
Serial.printf_P(PSTR("NTUN: %4.4f, %d, %4.4f, %4.4f, %4.4f, %4.4f, %4.4f,\n"),
|
||||||
Serial.print((float)((uint16_t)DataFlash.ReadInt())/100.0); // Yaw from IMU
|
(float)((uint16_t)DataFlash.ReadInt())/100.0,
|
||||||
Serial.print(comma);
|
DataFlash.ReadInt(),
|
||||||
Serial.print(DataFlash.ReadInt()); // wp_distance
|
(float)((uint16_t)DataFlash.ReadInt())/100.0,
|
||||||
Serial.print(comma);
|
(float)((uint16_t)DataFlash.ReadInt())/100.0,
|
||||||
Serial.print((float)((uint16_t)DataFlash.ReadInt())/100.0); // target_bearing - Bearing to Target
|
(float)DataFlash.ReadInt()/100.0,
|
||||||
Serial.print(comma);
|
(float)DataFlash.ReadInt()/100.0,
|
||||||
Serial.print((float)((uint16_t)DataFlash.ReadInt())/100.0); // nav_bearing - Bearing to steer
|
(float)DataFlash.ReadInt()/1000.0);
|
||||||
Serial.print(comma);
|
|
||||||
Serial.print((float)DataFlash.ReadInt()/100.0); // Altitude error
|
|
||||||
Serial.print(comma);
|
|
||||||
Serial.print((float)DataFlash.ReadInt()/100.0); // Airspeed
|
|
||||||
Serial.print(comma);
|
|
||||||
Serial.print((float)DataFlash.ReadInt()/1000.0); // nav_gain_scaler
|
|
||||||
Serial.println(comma);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read a performance packet
|
// Read a performance packet
|
||||||
@ -540,9 +537,11 @@ void Log_Read_Performance()
|
|||||||
Serial.print(pm_time);
|
Serial.print(pm_time);
|
||||||
Serial.print(comma);
|
Serial.print(comma);
|
||||||
for (int y = 1; y < 9; y++) {
|
for (int y = 1; y < 9; y++) {
|
||||||
if(y<3 || y>7) logvar = DataFlash.ReadInt();
|
if(y < 3 || y > 7){
|
||||||
else logvar = DataFlash.ReadByte();
|
logvar = DataFlash.ReadInt();
|
||||||
//if(y > 7) logvar = logvar/1000.f;
|
}else{
|
||||||
|
logvar = DataFlash.ReadByte();
|
||||||
|
}
|
||||||
Serial.print(logvar);
|
Serial.print(logvar);
|
||||||
Serial.print(comma);
|
Serial.print(comma);
|
||||||
}
|
}
|
||||||
@ -572,34 +571,24 @@ void Log_Read_Cmd()
|
|||||||
void Log_Read_Startup()
|
void Log_Read_Startup()
|
||||||
{
|
{
|
||||||
byte logbyte = DataFlash.ReadByte();
|
byte logbyte = DataFlash.ReadByte();
|
||||||
|
|
||||||
if (logbyte == TYPE_AIRSTART_MSG)
|
if (logbyte == TYPE_AIRSTART_MSG)
|
||||||
Serial.print("AIR START - ");
|
Serial.printf_P(PSTR("AIR START - "));
|
||||||
else if (logbyte == TYPE_GROUNDSTART_MSG)
|
else if (logbyte == TYPE_GROUNDSTART_MSG)
|
||||||
Serial.print("GROUND START - ");
|
Serial.printf_P(PSTR("GROUND START - "));
|
||||||
else
|
else
|
||||||
Serial.print("UNKNOWN STARTUP TYPE -");
|
Serial.printf_P(PSTR("UNKNOWN STARTUP - "));
|
||||||
Serial.print(DataFlash.ReadByte(), DEC);
|
|
||||||
Serial.println(" commands in memory");
|
Serial.printf_P(PSTR(" %d commands in memory\n"),(int)DataFlash.ReadByte());
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read an attitude packet
|
// Read an attitude packet
|
||||||
void Log_Read_Attitude()
|
void Log_Read_Attitude()
|
||||||
{
|
{
|
||||||
int log_roll;
|
Serial.printf_P(PSTR("ATT: %d, %d, %d\n"),
|
||||||
int log_pitch;
|
DataFlash.ReadInt(),
|
||||||
uint16_t log_yaw;
|
DataFlash.ReadInt(),
|
||||||
|
(uint16_t)DataFlash.ReadInt());
|
||||||
log_roll = DataFlash.ReadInt();
|
|
||||||
log_pitch = DataFlash.ReadInt();
|
|
||||||
log_yaw = (uint16_t)DataFlash.ReadInt();
|
|
||||||
|
|
||||||
Serial.print("ATT:");
|
|
||||||
Serial.print(log_roll);
|
|
||||||
Serial.print(comma);
|
|
||||||
Serial.print(log_pitch);
|
|
||||||
Serial.print(comma);
|
|
||||||
Serial.print(log_yaw);
|
|
||||||
Serial.println();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read a mode packet
|
// Read a mode packet
|
||||||
@ -612,25 +601,16 @@ void Log_Read_Mode()
|
|||||||
// Read a GPS packet
|
// Read a GPS packet
|
||||||
void Log_Read_GPS()
|
void Log_Read_GPS()
|
||||||
{
|
{
|
||||||
|
Serial.printf_P(PSTR("GPS: %ld, %d, %d, %4.7f, %4.7f, %4.4f, %4.4f, %4.4f, %4.4f\n"),
|
||||||
Serial.print("GPS:");
|
DataFlash.ReadLong(),
|
||||||
Serial.print(DataFlash.ReadLong()); // Time
|
(int)DataFlash.ReadByte(),
|
||||||
Serial.print(comma);
|
(int)DataFlash.ReadByte(),
|
||||||
Serial.print((int)DataFlash.ReadByte()); // Fix
|
(float)DataFlash.ReadLong() / t7,
|
||||||
Serial.print(comma);
|
(float)DataFlash.ReadLong() / t7,
|
||||||
Serial.print((int)DataFlash.ReadByte()); // Num of Sats
|
(float)DataFlash.ReadLong() / 100.0,
|
||||||
Serial.print(comma);
|
(float)DataFlash.ReadLong() / 100.0,
|
||||||
Serial.print((float)DataFlash.ReadLong()/t7, 7); // Lattitude
|
(float)DataFlash.ReadLong() / 100.0,
|
||||||
Serial.print(comma);
|
(float)DataFlash.ReadLong() / 100.0);
|
||||||
Serial.print((float)DataFlash.ReadLong()/t7, 7); // Longitude
|
|
||||||
Serial.print(comma);
|
|
||||||
Serial.print((float)DataFlash.ReadLong()/100.0); // Baro/gps altitude mix
|
|
||||||
Serial.print(comma);
|
|
||||||
Serial.print((float)DataFlash.ReadLong()/100.0); // GPS altitude
|
|
||||||
Serial.print(comma);
|
|
||||||
Serial.print((float)DataFlash.ReadLong()/100.0); // Ground Speed
|
|
||||||
Serial.print(comma);
|
|
||||||
Serial.println((float)DataFlash.ReadLong()/100.0); // Ground Course
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -651,14 +631,13 @@ void Log_Read_Raw()
|
|||||||
void Log_Read(int start_page, int end_page)
|
void Log_Read(int start_page, int end_page)
|
||||||
{
|
{
|
||||||
byte data;
|
byte data;
|
||||||
byte log_step=0;
|
byte log_step;
|
||||||
int packet_count=0;
|
int packet_count;
|
||||||
int page = start_page;
|
int page = start_page;
|
||||||
|
|
||||||
|
|
||||||
DataFlash.StartRead(start_page);
|
DataFlash.StartRead(start_page);
|
||||||
while (page < end_page && page != -1)
|
while (page < end_page && page != -1){
|
||||||
{
|
|
||||||
data = DataFlash.ReadByte();
|
data = DataFlash.ReadByte();
|
||||||
switch(log_step) // This is a state machine to read the packets
|
switch(log_step) // This is a state machine to read the packets
|
||||||
{
|
{
|
||||||
@ -713,8 +692,7 @@ void Log_Read(int start_page, int end_page)
|
|||||||
Log_Read_GPS();
|
Log_Read_GPS();
|
||||||
log_step++;
|
log_step++;
|
||||||
}else{
|
}else{
|
||||||
Serial.print("Error Reading Packet: ");
|
Serial.printf_P(PSTR("Error Reading Packet: %d\n"),packet_count);
|
||||||
Serial.print(packet_count);
|
|
||||||
log_step = 0; // Restart, we have a problem...
|
log_step = 0; // Restart, we have a problem...
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -723,16 +701,14 @@ void Log_Read(int start_page, int end_page)
|
|||||||
if(data == END_BYTE){
|
if(data == END_BYTE){
|
||||||
packet_count++;
|
packet_count++;
|
||||||
}else{
|
}else{
|
||||||
Serial.print("Error Reading END_BYTE ");
|
Serial.printf_P(PSTR("Error Reading END_BYTE: %d\n"),data);
|
||||||
Serial.println(data,DEC);
|
|
||||||
}
|
}
|
||||||
log_step = 0; // Restart sequence: new packet...
|
log_step = 0; // Restart sequence: new packet...
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
page = DataFlash.GetPage();
|
page = DataFlash.GetPage();
|
||||||
}
|
}
|
||||||
Serial.print("Number of packets read: ");
|
Serial.printf_P(PSTR("Number of packets read: %d\n"), packet_count);
|
||||||
Serial.println(packet_count);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -10,16 +10,16 @@ byte mavdelay = 0;
|
|||||||
|
|
||||||
static uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid)
|
static uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid)
|
||||||
{
|
{
|
||||||
if (sysid != mavlink_system.sysid)
|
if (sysid != mavlink_system.sysid){
|
||||||
{
|
|
||||||
return 1;
|
return 1;
|
||||||
}
|
|
||||||
else if (compid != mavlink_system.compid)
|
}else if(compid != mavlink_system.compid){
|
||||||
{
|
|
||||||
gcs.send_text(SEVERITY_LOW,"component id mismatch");
|
gcs.send_text(SEVERITY_LOW,"component id mismatch");
|
||||||
return 0; // XXX currently not receiving correct compid from gcs
|
return 0; // XXX currently not receiving correct compid from gcs
|
||||||
|
|
||||||
|
} else {
|
||||||
|
return 0; // no error
|
||||||
}
|
}
|
||||||
else return 0; // no error
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -53,7 +53,7 @@ void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint32_t param, ui
|
|||||||
case ALT_HOLD:
|
case ALT_HOLD:
|
||||||
mode = MAV_MODE_TEST2;
|
mode = MAV_MODE_TEST2;
|
||||||
break;
|
break;
|
||||||
case POSITION_HOLD:
|
case LOITER:
|
||||||
mode = MAV_MODE_AUTO;
|
mode = MAV_MODE_AUTO;
|
||||||
nav_mode = MAV_NAV_HOLD;
|
nav_mode = MAV_NAV_HOLD;
|
||||||
break;
|
break;
|
||||||
@ -65,14 +65,14 @@ void mavlink_send_message(mavlink_channel_t chan, uint8_t id, uint32_t param, ui
|
|||||||
mode = MAV_MODE_AUTO;
|
mode = MAV_MODE_AUTO;
|
||||||
nav_mode = MAV_NAV_RETURNING;
|
nav_mode = MAV_NAV_RETURNING;
|
||||||
break;
|
break;
|
||||||
case TAKEOFF:
|
//case TAKEOFF:
|
||||||
mode = MAV_MODE_AUTO;
|
// mode = MAV_MODE_AUTO;
|
||||||
nav_mode = MAV_NAV_LIFTOFF;
|
// nav_mode = MAV_NAV_LIFTOFF;
|
||||||
break;
|
// break;
|
||||||
case LAND:
|
//case LAND:
|
||||||
mode = MAV_MODE_AUTO;
|
// mode = MAV_MODE_AUTO;
|
||||||
nav_mode = MAV_NAV_LANDING;
|
// nav_mode = MAV_NAV_LANDING;
|
||||||
break;
|
// break;
|
||||||
}
|
}
|
||||||
uint8_t status = MAV_STATE_ACTIVE;
|
uint8_t status = MAV_STATE_ACTIVE;
|
||||||
uint8_t motor_block = false;
|
uint8_t motor_block = false;
|
||||||
|
@ -40,9 +40,6 @@ struct Location get_wp_with_index(int i)
|
|||||||
mem = (WP_START_BYTE) + (i * WP_SIZE);
|
mem = (WP_START_BYTE) + (i * WP_SIZE);
|
||||||
temp.id = eeprom_read_byte((uint8_t*)mem);
|
temp.id = eeprom_read_byte((uint8_t*)mem);
|
||||||
|
|
||||||
mem++;
|
|
||||||
temp.options = eeprom_read_byte((uint8_t*)mem);
|
|
||||||
|
|
||||||
mem++;
|
mem++;
|
||||||
temp.p1 = eeprom_read_byte((uint8_t*)mem);
|
temp.p1 = eeprom_read_byte((uint8_t*)mem);
|
||||||
|
|
||||||
@ -57,8 +54,10 @@ struct Location get_wp_with_index(int i)
|
|||||||
}
|
}
|
||||||
|
|
||||||
// Add on home altitude if we are a nav command
|
// Add on home altitude if we are a nav command
|
||||||
if(temp.options & WP_OPT_ALT_RELATIVE){
|
if(temp.id < 0x70){
|
||||||
|
//if((flight_options_mask & WP_OPT_ALT_RELATIVE) == 0){
|
||||||
temp.alt += home.alt;
|
temp.alt += home.alt;
|
||||||
|
//}
|
||||||
}
|
}
|
||||||
|
|
||||||
return temp;
|
return temp;
|
||||||
@ -77,7 +76,7 @@ void set_wp_with_index(struct Location temp, int i)
|
|||||||
//}
|
//}
|
||||||
|
|
||||||
// Store the location relatove to home
|
// Store the location relatove to home
|
||||||
if(temp.options & WP_OPT_ALT_RELATIVE){
|
if((flight_options_mask & WP_OPT_ALT_RELATIVE) == 0){
|
||||||
temp.alt -= home.alt;
|
temp.alt -= home.alt;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -86,9 +85,6 @@ void set_wp_with_index(struct Location temp, int i)
|
|||||||
|
|
||||||
eeprom_write_byte((uint8_t *) mem, temp.id);
|
eeprom_write_byte((uint8_t *) mem, temp.id);
|
||||||
|
|
||||||
mem++;
|
|
||||||
eeprom_write_byte((uint8_t *) mem, temp.options);
|
|
||||||
|
|
||||||
mem++;
|
mem++;
|
||||||
eeprom_write_byte((uint8_t *) mem, temp.p1);
|
eeprom_write_byte((uint8_t *) mem, temp.p1);
|
||||||
|
|
||||||
@ -167,12 +163,6 @@ void set_next_WP(struct Location *wp)
|
|||||||
// -----------------------------------------------
|
// -----------------------------------------------
|
||||||
target_altitude = current_loc.alt;
|
target_altitude = current_loc.alt;
|
||||||
|
|
||||||
// XXX YUCK!
|
|
||||||
if(prev_WP.id != MAV_CMD_NAV_TAKEOFF && prev_WP.alt != home.alt && (next_WP.id == MAV_CMD_NAV_WAYPOINT || next_WP.id == MAV_CMD_NAV_LAND))
|
|
||||||
offset_altitude = next_WP.alt - prev_WP.alt;
|
|
||||||
else
|
|
||||||
offset_altitude = 0;
|
|
||||||
|
|
||||||
// zero out our loiter vals to watch for missed waypoints
|
// zero out our loiter vals to watch for missed waypoints
|
||||||
loiter_delta = 0;
|
loiter_delta = 0;
|
||||||
loiter_sum = 0;
|
loiter_sum = 0;
|
||||||
|
@ -81,9 +81,6 @@ handle_no_commands()
|
|||||||
return;
|
return;
|
||||||
|
|
||||||
switch (control_mode){
|
switch (control_mode){
|
||||||
case LAND:
|
|
||||||
// don't get a new command
|
|
||||||
break;
|
|
||||||
|
|
||||||
//case GCS_AUTO:
|
//case GCS_AUTO:
|
||||||
// set_mode(LOITER);
|
// set_mode(LOITER);
|
||||||
|
@ -88,11 +88,9 @@
|
|||||||
#define FBW 3 // AUTO control
|
#define FBW 3 // AUTO control
|
||||||
#define AUTO 4 // AUTO control
|
#define AUTO 4 // AUTO control
|
||||||
#define GCS_AUTO 5 // AUTO control
|
#define GCS_AUTO 5 // AUTO control
|
||||||
#define POSITION_HOLD 6 // Hold a single location
|
#define LOITER 6 // Hold a single location
|
||||||
#define RTL 7 // AUTO control
|
#define RTL 7 // AUTO control
|
||||||
#define TAKEOFF 8 // controlled decent rate
|
#define NUM_MODES 8
|
||||||
#define LAND 9 // controlled decent rate
|
|
||||||
#define NUM_MODES 10
|
|
||||||
|
|
||||||
|
|
||||||
#define WP_OPT_ALT_RELATIVE (1<<0)
|
#define WP_OPT_ALT_RELATIVE (1<<0)
|
||||||
@ -207,18 +205,6 @@
|
|||||||
#define MASK_LOG_CMD (1<<8)
|
#define MASK_LOG_CMD (1<<8)
|
||||||
#define MASK_LOG_CUR (1<<9)
|
#define MASK_LOG_CUR (1<<9)
|
||||||
|
|
||||||
// bits in log_bitmask
|
|
||||||
#define LOGBIT_ATTITUDE_FAST (1<<0)
|
|
||||||
#define LOGBIT_ATTITUDE_MED (1<<1)
|
|
||||||
#define LOGBIT_GPS (1<<2)
|
|
||||||
#define LOGBIT_PM (1<<3)
|
|
||||||
#define LOGBIT_CTUN (1<<4)
|
|
||||||
#define LOGBIT_NTUN (1<<5)
|
|
||||||
#define LOGBIT_MODE (1<<6)
|
|
||||||
#define LOGBIT_RAW (1<<7)
|
|
||||||
#define LOGBIT_CMD (1<<8)
|
|
||||||
#define LOGBIT_CURRENT (1<<9)
|
|
||||||
|
|
||||||
// Waypoint Modes
|
// Waypoint Modes
|
||||||
// ----------------
|
// ----------------
|
||||||
#define ABS_WP 0
|
#define ABS_WP 0
|
||||||
|
@ -100,13 +100,13 @@ void calc_bearing_error()
|
|||||||
|
|
||||||
void calc_altitude_error()
|
void calc_altitude_error()
|
||||||
{
|
{
|
||||||
//if(control_mode == AUTO && offset_altitude != 0) {
|
altitude_error = next_WP.alt - current_loc.alt;
|
||||||
if(next_WP.options & WP_OPT_ALT_CHANGE || offset_altitude == 0) {
|
}
|
||||||
target_altitude = next_WP.alt;
|
|
||||||
|
|
||||||
}else{
|
void calc_altitude_smoothing_error()
|
||||||
|
{
|
||||||
// limit climb rates - we draw a straight line between first location and edge of waypoint_radius
|
// limit climb rates - we draw a straight line between first location and edge of waypoint_radius
|
||||||
target_altitude = next_WP.alt - ((wp_distance * offset_altitude) / (wp_totalDistance - g.waypoint_radius));
|
target_altitude = next_WP.alt - ((wp_distance * (next_WP.alt - prev_WP.alt)) / (wp_totalDistance - g.waypoint_radius));
|
||||||
|
|
||||||
// stay within a certain range
|
// stay within a certain range
|
||||||
if(prev_WP.alt > next_WP.alt){
|
if(prev_WP.alt > next_WP.alt){
|
||||||
@ -114,7 +114,6 @@ void calc_altitude_error()
|
|||||||
}else{
|
}else{
|
||||||
target_altitude = constrain(target_altitude, prev_WP.alt, next_WP.alt);
|
target_altitude = constrain(target_altitude, prev_WP.alt, next_WP.alt);
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
altitude_error = target_altitude - current_loc.alt;
|
altitude_error = target_altitude - current_loc.alt;
|
||||||
}
|
}
|
||||||
|
@ -647,7 +647,8 @@ void default_logs()
|
|||||||
{
|
{
|
||||||
|
|
||||||
// convenience macro for testing LOG_* and setting LOGBIT_*
|
// convenience macro for testing LOG_* and setting LOGBIT_*
|
||||||
#define LOGBIT(_s) (LOG_ ## _s ? LOGBIT_ ## _s : 0)
|
#define LOGBIT(_s) (MASK_LOG_##_s ? MASK_LOG_##_s : 0)
|
||||||
|
|
||||||
g.log_bitmask =
|
g.log_bitmask =
|
||||||
LOGBIT(ATTITUDE_FAST) |
|
LOGBIT(ATTITUDE_FAST) |
|
||||||
LOGBIT(ATTITUDE_MED) |
|
LOGBIT(ATTITUDE_MED) |
|
||||||
@ -658,7 +659,7 @@ void default_logs()
|
|||||||
LOGBIT(MODE) |
|
LOGBIT(MODE) |
|
||||||
LOGBIT(RAW) |
|
LOGBIT(RAW) |
|
||||||
LOGBIT(CMD) |
|
LOGBIT(CMD) |
|
||||||
LOGBIT(CURRENT);
|
LOGBIT(CUR);
|
||||||
#undef LOGBIT
|
#undef LOGBIT
|
||||||
|
|
||||||
g.log_bitmask.save();
|
g.log_bitmask.save();
|
||||||
|
@ -287,7 +287,7 @@ void set_mode(byte mode)
|
|||||||
update_auto();
|
update_auto();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case POSITION_HOLD:
|
case LOITER:
|
||||||
do_hold_position();
|
do_hold_position();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
@ -295,12 +295,6 @@ void set_mode(byte mode)
|
|||||||
do_RTL();
|
do_RTL();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case TAKEOFF:
|
|
||||||
break;
|
|
||||||
|
|
||||||
case LAND:
|
|
||||||
break;
|
|
||||||
|
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user