Gathiyo / arducopter

Automatically exported from code.google.com/p/arducopter
0 stars 0 forks source link

bug in control tuning log read function #331

Closed GoogleCodeExporter closed 8 years ago

GoogleCodeExporter commented 8 years ago

VC-450 frame with AP1 running 2.3

What steps will reproduce the problem?
1. reading log
2.
3.

What is the expected output? What do you see instead?
each log entry for CTUN has one 16 bit value at the end which is not right. The 
-17757 (in HEX is 0xBAA3) is the END_BYTE (0xBA) from the current entry plus 
the HEAD_BYTE1 (0xA3) from the next entry.

CTUN, 632, 122, 27, 128, 0, 3, 0, 28, 637, 0, 0, -17757
                                                 ^^^^^^ 
                                                    |________ caused by reading to much

This can bring the reading of the log out of sync. I found some lines in my 
logs which only have a period "." at the beginning of the line and nothing 
else. This is written because the reading state machine lost sync.
here is the code where it looses sync:

lines 820...833 quoted

        switch(log_step){
            case 0:
                if(data == HEAD_BYTE1)  // Head byte 1
                    log_step++;
                break;

            case 1:
                if(data == HEAD_BYTE2)  // Head byte 2
                    log_step++;
                else{
                    log_step = 0;
                    Serial.println(".");
                }
                break;

The problem is introduced when reading the CTUN entry of the log. The program 
writes 11 values but reads 11 plus one more integer.

// Write a control tuning packet. Total length : 22 bytes
static void Log_Write_Control_Tuning()
{
    DataFlash.WriteByte(HEAD_BYTE1);
    DataFlash.WriteByte(HEAD_BYTE2);
    DataFlash.WriteByte(LOG_CONTROL_TUNING_MSG);

    DataFlash.WriteInt(g.rc_3.control_in);              // 1
    DataFlash.WriteInt(sonar_alt);                      // 2
    DataFlash.WriteInt(baro_alt);                       // 3
    DataFlash.WriteInt(next_WP.alt);                    // 4
    DataFlash.WriteInt(nav_throttle);                   // 5
    DataFlash.WriteInt(angle_boost);                    // 6
    DataFlash.WriteInt(manual_boost);                   // 7
    DataFlash.WriteInt(climb_rate);                     // 8
    DataFlash.WriteInt(g.rc_3.servo_out);               // 9
    DataFlash.WriteInt(g.pi_alt_hold.get_integrator()); // 10
    DataFlash.WriteInt(g.pid_throttle.get_integrator());// 11

    DataFlash.WriteByte(END_BYTE);
}

// Read an control tuning packet
static void Log_Read_Control_Tuning()
{
    int16_t temp;

    Serial.printf_P(PSTR("CTUN, "));

    for(int8_t i = 0; i < 11; i++ ){
        temp = DataFlash.ReadInt();
        Serial.printf("%d, ", temp);
    }
    // read 13                          <======  these lines cause the sync problem
    temp = DataFlash.ReadInt();         <======  comment them out or delete them
    Serial.printf("%d\n", temp);        <======
}

Also starting with version 2.2b6 the sequence of some of the values written was 
changed. Mission planner does not account for those changes, this makes it hard 
when graphing since the labels do not match.
For example, if one will graph the sonar and selects the "Sonar Alt" Column, it 
will actually graph the "Nav Throttle" value. From what I could gathering by 
reading the code the following log entries have some values moved around: Nav 
Tuning, Control Tuning and Attitude.

So, some issues with Arducopter code and some issues with the Mission planner.

Original issue reported on code.google.com by ke6...@gmail.com on 5 Feb 2012 at 3:36

GoogleCodeExporter commented 8 years ago
Thanks for the catch.  I've just checked in a fix so this should come out in 
the next release.  
http://code.google.com/p/ardupilot-mega/source/detail?r=14221ce5a5b09a62e89f0fac
d783f2322ed54140

Original comment by rmackay...@gmail.com on 5 Feb 2012 at 8:07