mirror of https://github.com/ArduPilot/ardupilot
Alignment with APM
git-svn-id: https://arducopter.googlecode.com/svn/trunk@2293 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
6514dd8890
commit
6d056a569e
|
@ -122,6 +122,7 @@ erase_logs(uint8_t argc, const Menu::arg *argv)
|
||||||
// delay(1000);
|
// delay(1000);
|
||||||
//}
|
//}
|
||||||
|
|
||||||
|
// lay down a bunch of "log end" messages.
|
||||||
Serial.printf_P(PSTR("\nErasing log...\n"));
|
Serial.printf_P(PSTR("\nErasing log...\n"));
|
||||||
for(int j = 1; j < 4096; j++)
|
for(int j = 1; j < 4096; j++)
|
||||||
DataFlash.PageErase(j);
|
DataFlash.PageErase(j);
|
||||||
|
@ -189,23 +190,26 @@ byte get_num_logs(void)
|
||||||
{
|
{
|
||||||
int page = 1;
|
int page = 1;
|
||||||
byte data;
|
byte data;
|
||||||
byte log_step = 0;
|
byte log_step;
|
||||||
|
|
||||||
DataFlash.StartRead(1);
|
DataFlash.StartRead(1);
|
||||||
|
|
||||||
while (page == 1) {
|
while (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
|
||||||
case 0:
|
case 0:
|
||||||
if(data==HEAD_BYTE1) // Head byte 1
|
if(data==HEAD_BYTE1) // Head byte 1
|
||||||
log_step++;
|
log_step++;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 1:
|
case 1:
|
||||||
if(data==HEAD_BYTE2) // Head byte 2
|
if(data==HEAD_BYTE2) // Head byte 2
|
||||||
log_step++;
|
log_step++;
|
||||||
else
|
else
|
||||||
log_step = 0;
|
log_step = 0;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 2:
|
case 2:
|
||||||
if(data==LOG_INDEX_MSG){
|
if(data==LOG_INDEX_MSG){
|
||||||
byte num_logs = DataFlash.ReadByte();
|
byte num_logs = DataFlash.ReadByte();
|
||||||
|
@ -220,6 +224,7 @@ byte get_num_logs(void)
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// send the number of the last log?
|
||||||
void start_new_log(byte num_existing_logs)
|
void start_new_log(byte num_existing_logs)
|
||||||
{
|
{
|
||||||
int start_pages[50] = {0, 0, 0};
|
int start_pages[50] = {0, 0, 0};
|
||||||
|
@ -264,10 +269,10 @@ void get_log_boundaries(byte num_logs, byte log_num, int & start_page, int & end
|
||||||
{
|
{
|
||||||
int page = 1;
|
int page = 1;
|
||||||
byte data;
|
byte data;
|
||||||
byte log_step = 0;
|
byte log_step;
|
||||||
|
|
||||||
DataFlash.StartRead(1);
|
DataFlash.StartRead(1);
|
||||||
while (page = 1) {
|
while (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
|
||||||
{
|
{
|
||||||
|
@ -283,11 +288,14 @@ void get_log_boundaries(byte num_logs, byte log_num, int & start_page, int & end
|
||||||
break;
|
break;
|
||||||
case 2:
|
case 2:
|
||||||
if(data==LOG_INDEX_MSG){
|
if(data==LOG_INDEX_MSG){
|
||||||
|
|
||||||
byte num_logs = DataFlash.ReadByte();
|
byte num_logs = DataFlash.ReadByte();
|
||||||
|
|
||||||
for(int i=0;i<log_num;i++) {
|
for(int i=0;i<log_num;i++) {
|
||||||
start_page = DataFlash.ReadInt();
|
start_page = DataFlash.ReadInt();
|
||||||
end_page = DataFlash.ReadInt();
|
end_page = DataFlash.ReadInt();
|
||||||
}
|
}
|
||||||
|
|
||||||
if(log_num==num_logs)
|
if(log_num==num_logs)
|
||||||
end_page = find_last_log_page(start_page);
|
end_page = find_last_log_page(start_page);
|
||||||
|
|
||||||
|
@ -750,19 +758,18 @@ void Log_Read(int start_page, int end_page)
|
||||||
log_step++;
|
log_step++;
|
||||||
|
|
||||||
}else if(data == LOG_STARTUP_MSG){
|
}else if(data == LOG_STARTUP_MSG){
|
||||||
// not implemented
|
Log_Read_Startup();
|
||||||
log_step++;
|
log_step++;
|
||||||
|
}else {
|
||||||
}else if(data == LOG_GPS_MSG){
|
if(data == LOG_GPS_MSG){
|
||||||
Log_Read_GPS();
|
Log_Read_GPS();
|
||||||
log_step++;
|
log_step++;
|
||||||
|
|
||||||
}else{
|
}else{
|
||||||
Serial.printf_P(PSTR("Error P: %d\n"),packet_count);
|
Serial.printf_P(PSTR("Error Reading Packet: %d\n"),packet_count);
|
||||||
log_step = 0; // Restart, we have a problem...
|
log_step = 0; // Restart, we have a problem...
|
||||||
}
|
}
|
||||||
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 3:
|
case 3:
|
||||||
if(data == END_BYTE){
|
if(data == END_BYTE){
|
||||||
packet_count++;
|
packet_count++;
|
||||||
|
|
Loading…
Reference in New Issue