paparazzi-devel
[Top][All Lists]
Advanced

[Date Prev][Date Next][Thread Prev][Thread Next][Date Index][Thread Index]

Re: [Paparazzi-devel] problem with ground altitude


From: Felix Ruess
Subject: Re: [Paparazzi-devel] problem with ground altitude
Date: Mon, 2 Jun 2014 16:50:25 +0200

Hi,

FYI, this is merged into master and should work as expected now.
For rotorcrafts you need to replace ground_alt by GetAltRef() in your flight plans (examples are updated).

Please report back if you encounter any problems.

Cheers, Felix


On Mon, May 12, 2014 at 8:37 PM, alonso acuña <address@hidden> wrote:
One more thing that does seems to not work is crash detection.  Ground proximity warning is fine.


On Sat, May 10, 2014 at 6:31 PM, alonso acuña <address@hidden> wrote:
That's great AGL is working for fixedwing ap or sim targets out of the box. There is a problem in the Edit Waypoing dialog, it initially shows correct AGL but then when the altitude is edited the AGL does not show correctly.

Rotorcraft with the nps simulator do not appear to work well. The GPS initially gives an altitude above 3000m. So if NavSetGroundReferenceHere is not called then the ground_alt remains with the flight plan value but the a/c remains kilometers above. And if NavSetGroundReferenceHere is called then AGL shows 0 but strange things happen for example which clicking on the Altitude +5.0m button.  I don't have a real multirotor to test at this time.

Thanks


On Sat, May 10, 2014 at 4:04 PM, Gautier Hattenberger <address@hidden> wrote:
You can try it in nav_ref branch in paparazzi repository.

G.

Le 09/05/2014 17:36, alonso acuña a écrit :

Great.  Please note this needs to be fixed also in the Edit Waypoint dialog. I could not figure out how to do it. Thanks

On May 9, 2014 3:59 AM, "Gautier Hattenberger" <address@hidden> wrote:
Hi,

You're right that the ground alt should be useful in the telemetry, but in NAVIGATION_REF not GPS message. I will change that and server as well.

About the accuracy of the AGL displayed in the GCS, it is only the accuracy of the SRTM model that counts (for fixedwing, rotorcraft is a bit different). Using the ground_alt value as reference ground level might give you a correct agl height at the init point but will not follow the ground elevation when the terrain is not flat. I have seen 10 meters erros in the SRTM data at some places, but I think it is still better than using a constant reference altitude.
Of course if no there is no SRTM data, using ground_alt should be fine.

Gautier

Le 09/05/2014 09:56, alonso acuña a écrit :
These are the changes I have done. They allow for correct AGL in the GCS when there is no SRTM data.


conf/messages.xml
   
@@ -77,6 +77,7 @@

77     77           <field name="itow"       type="uint32" unit="ms"/>
78     78           <field name="utm_zone"   type="uint8"/>
79     79           <field name="gps_nb_err" type="uint8"/>
      80     +     <field name="ground_alt"        type="float"  unit="m"/>
80     81         </message>
81     82     
82     83         <message name="NAVIGATION_REF" id="9">

   
conf/settings/control/rotorcraft_guidance.xml

@@ -27,6 +27,7 @@

27     27     
28     28          <dl_settings NAME="NAV">
29     29            <dl_setting var="flight_altitude" MIN="0" STEP="0.1" MAX="400" module="navigation" unit="m" handler="SetFlightAltitude"/>
      30     +      <dl_setting MAX="4000" MIN="-260" STEP="1" VAR="ground_alt"/>
30     31            <dl_setting var="nav_heading" MIN="0" STEP="1" MAX="360" module="navigation" unit="1/2^12r" alt_unit="deg" alt_unit_coef="0.0139882"/>
31     32            <dl_setting var="nav_radius" MIN="-150" STEP="0.1" MAX="150" module="navigation" unit="m"/>
32     33          </dl_settings>

   
conf/settings/fixedwing_basic.xml

@@ -6,6 +6,7 @@

6     6        <dl_settings>
7     7          <dl_settings NAME="flight params">
8     8            <dl_setting MAX="1000" MIN="0" STEP="10" VAR="flight_altitude" shortname="altitude"/>
      9     +      <dl_setting MAX="4000" MIN="-260" STEP="1" VAR="ground_alt"/>
9     10            <dl_setting MAX="360" MIN="0" STEP="1" VAR="nav_course"/>
10     11            <dl_setting MAX="10" MIN="-10" STEP="5" VAR="nav_shift" module="subsystems/nav" handler="IncreaseShift" shortname="inc. shift"/>
11     12            <dl_setting MAX="0" MIN="0" STEP="1" VAR="autopilot_flight_time" shortname="flight time" module="autopilot" handler="ResetFlightTimeAndLaunch"/>

sw/airborne/subsystems/gps.c
   
@@ -44,7 +44,7 @@ static void send_gps(void) {

44     44        DOWNLINK_SEND_GPS(DefaultChannel, DefaultDevice, &gps.fix,
45     45            &gps.utm_pos.east, &gps.utm_pos.north,
46     46            &course, &gps.hmsl, &gps.gspeed, &climb,
47           -      &gps.week, &gps.tow, &gps.utm_pos.zone, &i);
      47     +      &gps.week, &gps.tow, &gps.utm_pos.zone, &i, &ground_alt);
48     48        if ((gps.fix != GPS_FIX_3D) && (i >= gps.nb_channels)) i = 0;
49     49        if (i >= gps.nb_channels * 2) i = 0;
50     50        if (i < gps.nb_channels && ((gps.fix != GPS_FIX_3D) || (gps.svinfos[i].cno > 0))) {

sw/ground_segment/tmtc/fw_server.ml
   
@@ -113,7 +113,11 @@ let log_and_parse = fun ac_name (a:Aircraft.aircraft) msg values ->

113     113                a.course  <- norm_course ((Deg>>Rad)(fvalue "course" /. 10.));
114     114                if !heading_from_course then
115     115                  a.heading <- a.course;
116           -          a.agl     <- a.alt -. float (try Srtm.of_wgs84 a.pos with _ -> 0);
      116     +          let srtmground = float (try Srtm.of_wgs84 a.pos with _ -> 0) in
      117     +          if srtmground = 0. then
      118     +            a.agl <- a.alt -. fvalue "ground_alt"
      119     +          else 
      120     +            a.agl <- a.alt -. srtmground;
117     121                if a.gspeed > 3. && a.ap_mode = _AUTO2 then
118     122                  Wind.update ac_name a.gspeed a.course
119     123              end


On Wed, May 7, 2014 at 7:05 PM, alonso acuña <address@hidden> wrote:
Hello. I am looking to revive this topic now that someone else has shown interest in have a useful AGL value in the GCS.  We ended up waiting for @Gautier to comment on the proposed changes, as indicated in my last email under "a)". 
I would be happy to work on this as I have already made these changes and in fact this makes it very difficut to update to latest master because of various incompatibilities introduced (for example new ground_alt field in GPS message).

thanks



On Thu, Sep 26, 2013 at 8:16 AM, Felix Ruess <address@hidden> wrote:
Hi Alonso,

IMHO trying to "fix" the SRTM data by hand is not a good option...
But using the ground_alt from the autopilot to display AGL if there is no SRTM data would probably be better than what we currently have.
@Gautier, what do you think?

For the second problem, you are of course free to not use NavSetGroundReferenceHere in your flight plan and just set it correctly.
This is just to make it easier if you go flying somewhere else without having to change your flight plan...

Cheers, Felix


On Tue, Sep 24, 2013 at 2:24 AM, alonso acuña <address@hidden> wrote:
Thanks for the info. I am still trying to figure out the best way to handle AGL. I have 2 simple problems that make things very complicated:
- there is a 10m error in SRTM versus GPS for the entire area around our testing site
NavSetGroundReferenceHere sets altitude that vary by a few meters depending on weather etc
So as it is the AGL number seen on the GCS is useless.

For the first problem I have some ideas (all of them assume a level field otherwise is gets even trickier):
  a)  ignore SRTM and use the airborne ground_alt value . This proves to require several changes in various places, like getting the value from aircraft, using it in the server to calculate AGL, fix crash detection and some other places which display absolute altitude when SRTM is not available.
  b) ignore SRTM and use a fixed altitude set in the flight plan. I haven't tried this but might be just as much work as a)
  c) fix the SRTM data. I haven't investigated this yet. Perhaps a script could be made (or exists?) to apply the fix for a given area. Or one could tell Paparazzi to apply an offset to all points in a given area and if this info is made public and part of the software it would helf others from day one.

For the second problem I think it would be easier just to give the airborne code the initial value in the flight plan (which is known to be the correct value) and not use NavSetGroundReferenceHere.
One could also set the value again if landing at a different location. But then I wonder why is this not the default behaviour?

I appreciate any guidance on where it would be best to direct my efforts and also whould like to hear how others work around or fix these issues.  Thanks.




On Mon, Sep 23, 2013 at 3:34 PM, Felix Ruess <address@hidden> wrote:
Hi Alonso,

ground_alt in the airborne code a semi-fixed value. It gets initialized with the GROUND_ALT from the flight plan and set to current altitude if you call NavSetGroundReferenceHere() (e.g. from GeoInit in flight plan). So this is normally only the ground altitude of the point where you took off and not the altitude of the hill you are flying over...

Regarding the update of waypoint altitudes:
- Fixedwing firmware uses UTM coordinates with height above MSL as altitude. These are updated accordingly if you call NavSetGroundReferenceHere().
- Rotorcraft firmware uses ENU (EastNorthUp) waypoint coordinates internally with coordinates relative to the ENU origin (so Up is zero at ground_alt) and hence no need to update the waypoints altitudes.

Hope that helps,
Cheers, Felix


On Wed, Sep 18, 2013 at 7:15 PM, alonso acuña <address@hidden> wrote:
Sorry I didn't think of that case with the hill. I've been focused on my simple case which is a level field with no good srtm data.  

The hill case got me thinking about how would the aircraft know about the hill so I have been looking at the code trying to find where the airborne code ground alt is set and the only one I could find was the initial NavSetGroundReferenceHere(). I hope I am missing something because otherwise the ground is fixed for the aircraft always and trying to land at a different altitude would not work.
Is there any documentation on how all of this works? I found this http://paparazzi.enac.fr/wiki/Demystified/Altitude_and_Height but still don't fully understand.

I also found that a few modules like the photogrammetry calculator use the GROUND_ALT which is the static value set at the top of the flight plan file. Is that ok or should they use the updated ground_alt? Also GROUND_ALT seems to be used only as an initial value in the navigation code, is that the case and should it be documented as just an initial reference at http://paparazzi.enac.fr/wiki/Flight_Plans

Finally at http://paparazzi.enac.fr/wiki/Demystified/Altitude_and_Height it says "E.g. if in your flight plan you have alt="50" ground_alt="0", your default waypoint altitude (above mean sea level, not above ground) is set to 50m and your ground altitude to 0m. Now, if your ground altitude is actually 65m above sea level, the geo_init will set this. But your waypoints are still set to the 50m above sea level, so they will be -15m from your current altitude".  In sw/airborne/subsystems/navigation/common_nav.h  I found 
   #define NavSetGroundReferenceHere() ({ nav_reset_reference(); nav_update_waypoints_alt(); FALSE; })  
so it appears that waypoint alt is in fact updated?   But then I also found in  sw/airborne/firmwares/rotorcraft/navigation.h 
   #define NavSetGroundReferenceHere() ({ nav_reset_reference(); FALSE; })
   #define NavSetAltitudeReferenceHere() ({ nav_reset_alt(); FALSE; })   
and these work completely different with no waypoint update.  I wonder why they are 2 of these. Is the documentation correct in saying that waypoint alt is not updated ? Does it work different in rotorcrafts?

I appreciate your attention. Thanks



On Wed, Sep 18, 2013 at 8:05 AM, AJ Kochevar <address@hidden> wrote:

How would your solution handle terrain like sermon days does currently.  Like your aircraft flying over a large say 100 foot hill.  Your way would say you are 100 above ground but in fact you are 0.  There is a reason its called " Above ground". 

On Sep 17, 2013 11:43 PM, "alonso acuña" <address@hidden> wrote:
I still would think that it is better to provide a fixed altitude in the flight plan and not check by GPS because the GPS reading might be different each day according to weather conditions, antenna position etc. But anyway perhaps the problem is that the GCS continues to use the original ground_level even after the aircraft has corrected its value by GPS. I think it should be the same in both regardless of how the ground level is determined.


On Wed, Sep 18, 2013 at 12:23 AM, Hector Garcia de Marina <address@hidden> wrote:

Because it is a static error, just an offset. Ground level is just a relative reference, the important point for almost all applications is to know where the ground is wrt the plane, and not wrt the mean sea level (what you are asking for). If you need to know precisely the later, then indeed you need to do something else.

On 18 Sep 2013 07:33, "alonso acuña" <address@hidden> wrote:
I have learned a few things tonight:
- in order to not use SRTM data the files in data/srtm need to be deleted. Simply running the gcs without the -strm option is not enough as the data still gets used.
- the ground level as shown in GCS has no relation to ground level as known to the airborne code. To see or change airborne code's ground level add <dl_setting MAX="4000" MIN="0" STEP="1" VAR="ground_alt"/> to conf/settings/fixedwing_basic.xml or similar file you are using.
- there is no warning when the airborne ground level is very different to the SRTM or to GCS ground level. So for example when the aircraft goes into this part of the flight plan:
   <block name="final">
      <exception cond="ground_alt + 10 > GetPosAlt()" deroute="flare"/>
  it will be doing the flare at the wrong altitude.

If several people are telling me that GPS given altitude is not accurate then why is the airborne code ground level set from GPS at the beggining of the flight plan? Why not use the ground_level value from the flight plan?






On Tue, Sep 17, 2013 at 7:13 PM, Eduardo lavratti <address@hidden> wrote:
SRTM and google have the same error. GPS vertical error is 3 times greater than horizontal error.

You get correct altitude using precision gps or altimetric map + geoidal correction.



Date: Tue, 17 Sep 2013 18:26:27 -0600
From: address@hidden
To: address@hidden
Subject: Re: [Paparazzi-devel] problem with ground altitude


Hello. I have checked once again today. We had 3m GPS accuracy and double checked with a portable GPS and we continue to be standing about 10m above what SRTM data and Google Earth think is the ground level. I hope someone can help me to see what options I have and answer the questions in my original email. Will be much appreciated.


On Tue, Sep 17, 2013 at 12:58 AM, alonso acuña <address@hidden> wrote:

This is what I thought but the difference between SRTM and GPS has remained around 10 to 13m on the 4 days over the past weeks that we have been on the field. GCS indicates precision of about 5m. I suspect this is not going to change and might be an error in the SRTM data.

On Sep 17, 2013 12:47 AM, "Hector Garcia de Marina" <address@hidden> wrote:

Hi Alonso,

This behavior is completely normal. Your GPS has an static error. That depends on how is the signal (weather, solar activity, number of satellites, their position...) at the moment of the reception. Also it depends on the receiver itself.

The receiver uses to tell you how good is its estimation with the HDOP, VDOP and other information, check these acronyms in wikipedia for more information.

The same case is for the 2D position.

Cheers,

On 17 Sep 2013 07:29, "alonso acuña" <address@hidden> wrote:
Hello. It appears that there is a difference of about 10 meters in the reported ground altitude in SRTM date and google earth with the altitude reported by GPS at this location. So when the aircraft is on the ground it says AGL 10 and exported kml shows the path 10 meters above ground in Google Earth. 
I have read the code for NavSetGroundReferenceHere flight plan command and it seems it makes the aircraft take the current GPS altitude as ground level which seems a good thing. However this does not fix things in the GCS.
How is the AGL shown in GPS calculated? 
How can I make it not use SRTM data? 
How can I can I tell what the aircraft thinks the ground level is ?
And what is the ground_level parameter in flight plan for?

Thanks for the help.

Alonso

_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel


_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



_______________________________________________ Paparazzi-devel mailing list address@hidden https://lists.nongnu.org/mailman/listinfo/paparazzi-devel

_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel


_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel


_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel





_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel


_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel


_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel




_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



reply via email to

[Prev in Thread] Current Thread [Next in Thread]