mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_Terrain: make TERRAIN_MARGIN a float
it turns out very large margins are needed for some locations
This commit is contained in:
parent
e5bde1a085
commit
a412795045
@ -63,10 +63,10 @@ const AP_Param::GroupInfo AP_Terrain::var_info[] = {
|
||||
// @Param: MARGIN
|
||||
// @DisplayName: Acceptance margin
|
||||
// @Description: Margin in centi-meters to accept terrain data from the GCS. This can be used to allow older terrain data generated with less accurate latitude/longitude scaling to be used
|
||||
// @Units: cm
|
||||
// @Range: 2 30000
|
||||
// @Units: m
|
||||
// @Range: 0.05 50000
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO("MARGIN", 3, AP_Terrain, margin, 2),
|
||||
AP_GROUPINFO("MARGIN", 3, AP_Terrain, margin, 0.05),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
@ -62,7 +62,7 @@
|
||||
// we allow for a 2cm discrepancy in the grid corners. This is to
|
||||
// account for different rounding in terrain DAT file generators using
|
||||
// different programming languages
|
||||
#define TERRAIN_LATLON_EQUAL(v1, v2) (labs((v1)-(v2)) <= unsigned(margin.get()))
|
||||
#define TERRAIN_LATLON_EQUAL(v1, v2) (labs((v1)-(v2)) <= unsigned(margin.get()*100))
|
||||
|
||||
#if TERRAIN_DEBUG
|
||||
#include <assert.h>
|
||||
@ -352,7 +352,7 @@ private:
|
||||
|
||||
// parameters
|
||||
AP_Int8 enable;
|
||||
AP_Int16 margin;
|
||||
AP_Float margin;
|
||||
AP_Int16 grid_spacing; // meters between grid points
|
||||
AP_Int16 options; // option bits
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user