Owne / ardupilot-mega

Automatically exported from code.google.com/p/ardupilot-mega
0 stars 0 forks source link

Logging or log reading problem #302

Closed GoogleCodeExporter closed 8 years ago

GoogleCodeExporter commented 8 years ago
What steps will reproduce the problem?
1. Use Logging capabilities
2. Read log using a serial program, such as putty

What is the expected output? What do you see instead?
Expected: read logged information as stored
Instead: Logging for a short time results in a huge record. Wrong length and 
values returned at dumping.  

What version of the product are you using? On what operating system?
APM 2.011, Arduino 0021, OpenSuSE 11.3 64 bit

Please provide any additional information below.

ArduPilotMega] logs
logs enabled:  ATTITUDE_MED GPS PM MODE CMD CUR

1 logs available for download
Log number 1,    start page 2,   end page 4096

Log] dump 1
Dumping Log number 1,    start page 2,   end page 4096
Error Reading Packet: 8594
CMD:0,255,255,-1,-1,-1, 
PM:22080,1,243,0,0,0,0,0,1000, 
ATT: -2, 1, -29539
GPS: 0, 0, 0, 0.0000000, 0.0000000, 0.0000, -0.2600, 0.0000, 0.0000
ATT: -3, 2, -29540
GPS: 0, 0, 0, 0.0000000, 0.0000000, 0.0000, -1.0600, 0.0000, 0.0000
...
ATT: -1462, -8568, 28323
CTUN:-0.72,0.00,-14.62,-0.18,0.00,-85.68,0.00,0.00,-0.00, 
NTUN: 283.2300, 16, 270.0000, 270.0000, -2.1900, 0.0000, 1.0000,
GPS: 123942500, 1, 13, 49.4381220, 8.6526928, 103.0000, 121.3200, 1.9400, 
200.4600
Number of packets read: -23872
Log read complete
logs enabled:  ATTITUDE_MED GPS PM MODE CMD CUR

1 logs available for download
Log number 1,    start page 2,   end page 4096

Log]

ArduPilotMega] logs
logs enabled:  ATTITUDE_MED GPS PM MODE CMD

1 logs available for download
Log number 1,    start page 2,   end page 2069

Log] dump 1
Dumping Log number 1,    start page 2,   end page 2069
Error Reading Packet: 8594
CMD:0,255,255,-1,-1,-1, 
ATT: 1, 2, 3
GPS: 0, 0, 0, 0.0000000, 0.0000000, 0.0000, -0.1700, 0.0000, 0.0000
...
GPS: 0, 0, 0, 0.0000000, 0.0000000, 0.0000, -0.4400, 0.0000, 0.0000
ATT: -106, -182, -29651
Error Reading END_BYTE: 255
Error Reading Packet: 9026
NTUN: 169.1800, 16, 270.0000, 270.0000, -2.6300, 0.0000, 1.0000,
GPS: 123942750, 1, 13, 49.4381180, 8.6526899, 102.9900, 121.7600, 1.6300, 
201.6200
ATT: 13159, -8899, 14120
CTUN:-0.72,0.00,131.59,-0.18,0.00,-88.99,0.00,0.00,0.00, 
NTUN: 141.2000, 16, 270.0000, 270.0000, -2.6300, 0.0000, 1.0000,
GPS: 123943000, 1, 13, 49.4381140, 8.6526861, 102.9900, 121.7600, 1.6600, 
203.6000
...
GPS: 0, 0, 0, 0.0000000, 0.0000000, 0.0000, -0.4400, 0.0000, 0.0000
ATT: -106, -182, -29651
Number of packets read: 9473
Log read complete
logs enabled:  ATTITUDE_MED GPS PM MODE CMD

1 logs available for download
Log number 1,    start page 2,   end page 2069

Log] 

Maybe related to bug: 294 ?

Original issue reported on code.google.com by el_andre...@hotmail.com on 26 Mar 2011 at 7:59

GoogleCodeExporter commented 8 years ago
did you do a log erase since you put on 2.011??

Original comment by Meee...@gmail.com on 26 Mar 2011 at 2:39

GoogleCodeExporter commented 8 years ago
Same behaviour after erasing. APM reports about 2000 pages for only 20 sec of 
logging. The problem was already in APM 2.0. In 1.02 logging worked, but not 
all data was dumped and a part repeated.

Original comment by el_andre...@hotmail.com on 26 Mar 2011 at 4:19

GoogleCodeExporter commented 8 years ago
I can't replicate this. Can you try with just the default log fields?

Original comment by analogue...@gmail.com on 27 Mar 2011 at 1:04

GoogleCodeExporter commented 8 years ago
I uploaded again APM 2.011 (now compiled with Arduino 022). In the CLI, I 
erased EEPROM via "setup/reset", erased flash memory via "logs/erase". Same 
problem as before:

ArduPilotMega] logs
logs enabled:  ATTITUDE_MED GPS PM MODE CMD

1 logs available for download
Log number 1,    start page 2,   end page 2063

Log] dump 1
Dumping Log number 1,    start page 2,   end page 2063
Error Reading Packet: 8594
CMD:0,0,0,0,0,0, 
ATT: -1, -3, 3
GPS: 0, 0, 0, 0.0000000, 0.0000000, 0.0000, -0.3400, 0.0000, 0.0000
[...]
ATT: 645, -250, -30013
GPS: 0, 0, 0, 0.0000000, 0.0000000, 0.0000, -0.3400, 0.0000, 2.5500
Error Reading END_BYTE: 255
Error Reading Packet: 8889
GROUND START -  0 commands in memory
CMD:0,0,0,0,0,0, 
ATT: -1, -3, 3
GPS: 0, 0, 0, 0.0000000, 0.0000000, 0.0000, -0.3400, 0.0000, 0.0000
[...]
ATT: 645, -250, -30013
GPS: 0, 0, 0, 0.0000000, 0.0000000, 0.0000, -0.3400, 0.0000, 2.5500
Number of packets read: 9185
Log read complete
logs enabled:  ATTITUDE_MED GPS PM MODE CMD

1 logs available for download
Log number 1,    start page 2,   end page 2063

Log] 

In APM 1.0 it worked flawlessly. In APM 1.02 it seemed to leave a part of the 
log away and repeated some parts of the values. In APM 2.0 and 2.011 it does 
not log at all. 

Maybe erasing is not working correctly? Last time a downgraded to APM 1.0 and 
the "old" data, before upgrading to 2.0 and erasing, seemed to be still there.

Original comment by el_andre...@hotmail.com on 27 Mar 2011 at 7:52

GoogleCodeExporter commented 8 years ago
Assuming there is no bug in the software, what would happen, if for some 
strange reason, my Atmel AT45DB161D memory chip would still have a 528-byte 
pagesize instead of 512-bytes?

Original comment by el_andre...@hotmail.com on 28 Mar 2011 at 9:53

GoogleCodeExporter commented 8 years ago
I think a found a possible source for the bug. The splitting of the page 
address shifts the bits wrong. Take for example DataFlash_Class::PageErase:

void DataFlash_Class::PageErase (unsigned int PageAdr)
{
  dataflash_CS_inactive();                                                              //make sure to toggle CS signal in order
  dataflash_CS_active();                                                                //to reset Dataflash command decoder
  dataflash_SPI_transfer(DF_PAGE_ERASE);   // Command
  dataflash_SPI_transfer((unsigned char)(PageAdr >> 6));    //upper part of page address
  dataflash_SPI_transfer((unsigned char)(PageAdr << 2));    //lower part of page address and MSB of int.page adr.
  dataflash_SPI_transfer(0x00);            // "dont cares"
  dataflash_CS_inactive();               //initiate flash page erase
  dataflash_CS_active();
  while(!ReadStatus());
}

PageAdr contains the adress of the page in following format: 
PageAdr = 0 0 0 0 P11 P10 P9 P8 P7 P6 P5 P4 P3 P2 P1 P0

where the P's mark the page adress bits. Now, documentation of the memory chips 
says that for the 512-byte pagesize, 3 do-not-care bits have to be sent, then 
12 page address bits and the 9 do-not-care bits.

Consider the line: 
dataflash_SPI_transfer((unsigned char)(PageAdr >> 6));

This shifts PageAdr by six bitand takes then the 8 rightmost bit of it, i.e. 

PageAdr >> 6 = 0 0 0 0 0 0 0 0 0 0 P11 P10 P9 P8 P7 P6 
(unsigned char)(PageAdr >> 6) = 0 0 P11 P10 P9 P8 P7 P6

So one do-not-care bit is missing! Consider now the line: 
dataflash_SPI_transfer((unsigned char)(PageAdr << 2));

which results in

PageAdr << 2 = 0 0 P11 P10 P9 P8 P7 P6 P5 P4 P3 P2 P1 P0 0 0
(unsigned char)(PageAdr << 2) = P5 P4 P3 P2 P1 P0 0 0

And then the line: 

dataflash_SPI_transfer(0x00); 

fills up with 8 do-not-care bits. So in total the code sends following to the 
memory chip:

0 0 P11 P10 P9 P8 P7 P6 P5 P4 P3 P2 P1 P0 0 0 0 0 0 0 0 0 0 0

So one bit is missing in front and one is too much at the end. A corrected 
version of the function would be:

void DataFlash_Class::PageErase (unsigned int PageAdr)
{
  dataflash_CS_inactive();                                                              //make sure to toggle CS signal in order
  dataflash_CS_active();                                                                //to reset Dataflash command decoder
  dataflash_SPI_transfer(DF_PAGE_ERASE);   // Command
  dataflash_SPI_transfer((unsigned char)(PageAdr >> 7));    //upper part of page address
  dataflash_SPI_transfer((unsigned char)(PageAdr << 1));    //lower part of page address and MSB of int.page adr.
  dataflash_SPI_transfer(0x00);            // "dont cares"
  dataflash_CS_inactive();               //initiate flash page erase
  dataflash_CS_active();
  while(!ReadStatus());
}

I have not tried yet but will do it later at home.

Andrés

Original comment by el_andre...@hotmail.com on 28 Mar 2011 at 12:47

GoogleCodeExporter commented 8 years ago
Changing in DataFlash.cpp all lines  

dataflash_SPI_transfer((unsigned char)(PageAdr >> 6));  
dataflash_SPI_transfer((unsigned char)(PageAdr << 2));

into 

dataflash_SPI_transfer((unsigned char)(PageAdr >> 7));  
dataflash_SPI_transfer((unsigned char)(PageAdr << 1));

Solves the problem. I did a reset and erase and was able to log normally. The 
original lines would be correct for 528 byte pages.

Andrés

Original comment by el_andre...@hotmail.com on 28 Mar 2011 at 4:18

GoogleCodeExporter commented 8 years ago
[deleted comment]
GoogleCodeExporter commented 8 years ago
please refer to http://www.atmel.com/dyn/resources/prod_documents/doc3500.pdf 
page 28, about addressing 528 byte pages.

Original comment by Meee...@gmail.com on 29 Mar 2011 at 10:06

GoogleCodeExporter commented 8 years ago
I know that document. That's the one I used to chase the bug. Thank you anyway. 
The bug is actually that the page adress code treats the chip in 528 byte mode 
instead of 512 byte mode. What mode is standard in APM? From dataflash.cpp I 
would say 512.

This bug might be longer in the code, but not until now it seemed to break 
logging (at least for me). In APM 1.02 I had problems too (repeating logs and 
only half memory space was usable) and in 1.0 it "seemed" to work right, which 
does not mean that the bug was already there...

Original comment by el_andre...@hotmail.com on 29 Mar 2011 at 11:13

GoogleCodeExporter commented 8 years ago
posibly fixed by 306

Original comment by Meee...@gmail.com on 29 Mar 2011 at 1:53

GoogleCodeExporter commented 8 years ago
Maybe 306 had to do something with the probel it, but still the code for the 
page address coding is missing one bit and thus only half the memory is 
actually being used. 

Original comment by el_andre...@hotmail.com on 29 Mar 2011 at 6:57

GoogleCodeExporter commented 8 years ago
Ok i agree we are addressing it wrong, but wondering how it has gotton this far 
without being a problem.

i believe this is the reason

“Power of 2” binary page size Configuration Register is a user-programmable 
nonvolatile register that allows the
page size of the main memory to be configured for binary page size (512-bytes) 
or standard Atmel® DataFlash
page size (528-bytes). The “power of 2” page size is a one-time 
programmable configuration register and
once the device is configured for “power of 2” page size, it cannot be 
reconfigured again. The devices are
initially shipped with the page size set to 528-bytes. The user has the option 
of ordering binary page size (512
bytes) devices from the factory.

they come standard for 528, not 512, and since its a write once option the 
library is addressing it as the 528 because it is still the 528, it has never 
been changed to the 512. but is also wasting those extra 16 bytes. Ive had a 
log running to use nearly all the flash and never noticed it miss anything. So 
i believe you are partly correct about the addressing. but no change is needed.

Original comment by Meee...@gmail.com on 30 Mar 2011 at 12:50

GoogleCodeExporter commented 8 years ago
If all chips are truly in 528 mode, then the code for the page address should 
be right. However, the code is sort of hybrid at the moment. The WriteByte and 
ReadByte functions need to be corrected, because they assume that the buffer is 
512 bytes large. A value of 528 should be used instead, to be able to really 
fill up the memory.

I'll test again on my board with the original page code later at home. Maybe 
bug 306 was really the source for problems. Or, I got a 512 byte chip due to 
some strange reason...

Original comment by el_andre...@hotmail.com on 30 Mar 2011 at 1:20

GoogleCodeExporter commented 8 years ago
I had a chance to test the original page address coding and I get directly the 
error reported. I'm quiet confident that my chip is in 512 bytes mode. Now the 
question is, if other chips have also 512 bytes and how to handle a possible 
mix between 512 and 528 byte chips? The solution would be to read out the mode 
somehow, but the chip seems not to offer a command to read this out... 

Original comment by el_andre...@hotmail.com on 30 Mar 2011 at 3:49

GoogleCodeExporter commented 8 years ago
I found following in the documentation of the chip:

Bit zero in the Status Register indicates whether the page size of the main 
memory array is configured for “power
of 2” binary page size (512-bytes) or standard DataFlash page size 
(528-bytes). If bit zero is a one, then the page
size is set to 512-bytes. If bit zero is a zero, then the page size is set to 
528-bytes.

This means that we should be able to use the status register to decide which 
type of reading is necessary...

Original comment by el_andre...@hotmail.com on 30 Mar 2011 at 4:00

GoogleCodeExporter commented 8 years ago
So I have the ultimate evidence that my chip works in 512 bytes mode. I wrote a 
function to read the page size from the status register:

unsigned int DataFlash_Class::PageSize()
{ 
  byte tmp;

  dataflash_CS_inactive();    // Reset dataflash command decoder
  dataflash_CS_active();     

  // Read status command
  dataflash_SPI_transfer(DF_STATUS_REGISTER_READ);
  tmp = dataflash_SPI_transfer(0x00);

  return(528-((tmp&0x01)<<4));  // if first bit 1 then 512 else 528 bytes
}

Writing the value of this function to the Serial, by calling it e.g. in the 
one_second_loop(), delivers:

Init ArduPilotMega (unstable development version)

Free RAM: 2086
load_all took 1544us
using 2076 bytes of memory
<startup_IMU_ground> Warming up ADC...
<startup_IMU_ground> Beginning IMU calibration; do not move plane
Init Gyro**********Init Accel********** abs_pressure 100309
barometer calibration complete.
MSG: reset_control_switch0
G MTK1.4 OK
Flash memory Page size 512
U▒▒Flash memory Page size 512
U@5Flash memory Page size 512
U.▒Flash memory Page size 512
...

I would be interested in knowing what values your board dumps...

Original comment by el_andre...@hotmail.com on 30 Mar 2011 at 5:31

GoogleCodeExporter commented 8 years ago
I did some changes on DataFlash.h and DataFlash.h (see attached files). The 
code should treat now both cases 528 and 512 bytes correctly.

BTW the code seems to assume that the first page in the chip has the address 1. 
From the datashett I would rather say it should be 0, so that at the moment one 
page is not being used... 

Original comment by el_andre...@hotmail.com on 30 Mar 2011 at 8:15

Attachments:

GoogleCodeExporter commented 8 years ago
Mine is set to 528, Register returns 172 = bit 0 is 0. If bit zero is a zero, 
then the page size is set to 528-bytes.

How old/new is your imu board?

Original comment by Meee...@gmail.com on 31 Mar 2011 at 12:45

GoogleCodeExporter commented 8 years ago
Well, that explains why I have problems and you not ;)

I bought the boards about mid November 2010 from two retailers here in Germany. 
However, one never knows for how long the boards were laying around before I 
got them... Maybe the photos I attached help to find out how old my IMU is.

I myself find the logging option very appealing and one of the reasons why I 
bought APM, but not everybody uses it. There might be some other 512 boards out 
there. I guess the best option would be to make the DataFlash class to 
recognize the page size automatically.

Original comment by el_andre...@hotmail.com on 31 Mar 2011 at 3:36

GoogleCodeExporter commented 8 years ago
Sorry, one more question. How did you read out the status register? Did you use 
ReadStatus()? I'm just asking because ReadStatus() does not deliver the full 
content of the register, as it returns  tmp&0x80. That's why I wrote a new 
function to read it out. If you use the original ReadStatus(), you'll always 
get 528 mode...

Original comment by el_andre...@hotmail.com on 31 Mar 2011 at 3:43

GoogleCodeExporter commented 8 years ago
i used
unsigned int DataFlash_Class::PageSize()
{ 
  byte tmp;

  dataflash_CS_inactive();    // Reset dataflash command decoder
  dataflash_CS_active();     

  // Read status command
  dataflash_SPI_transfer(DF_STATUS_REGISTER_READ);
  tmp = dataflash_SPI_transfer(0x00);

  return(tmp);
}

Original comment by Meee...@gmail.com on 31 Mar 2011 at 3:56

GoogleCodeExporter commented 8 years ago
Is this issue resolved?  I cannot reproduce it.

Original comment by dewei...@gmail.com on 2 Apr 2011 at 12:34

GoogleCodeExporter commented 8 years ago
Appears to be an isolated issue due to non-standard hardware.

Original comment by dewei...@gmail.com on 2 Apr 2011 at 3:06

GoogleCodeExporter commented 8 years ago
I solved the issue by changing minimally the DataFlash class. In comment #18 I 
attached a version of DataFlash, which should handle both cases correctly by 
checking the pagesize (someone with a 528 chip should test it out). It's up to 
you to decide if you want to include these changes into the development 
version. I do not have SVN commit rights... Although my hardware is 
non-standard - for reason I do not know of - you cannot discard that other 
users might also have such chips. Maybe even one wrong batch was delivered?

Even for the right 528 page-size chip, the original code has a non-critical 
bug, because it assumes that the buffer sitze if 512 and not 528 (16 bytes 
space are wasted for the 528 chip). Moreover, the DataFlash class and the 
loggin function in Log.pde assume that the address of the first page is 1 and 
not 0. Therefore, one page of memory is not being used at the moment (also a 
non-critical bug). So in total the code is wasting more than 60 kB for the 528 
byte chip at the moment.

Original comment by el_andre...@hotmail.com on 2 Apr 2011 at 7:19

GoogleCodeExporter commented 8 years ago
[deleted comment]
GoogleCodeExporter commented 8 years ago
I've been bitten by the same problem perhaps. I've never been able to get the 
logs to behave properly. Will give this a try.

Original comment by jasonshort on 17 Apr 2011 at 11:28