AP_Math: avoid using struct Location

clang reports this could be a problem when compiling under some EABIs.  Remove it from most places as it is just noise, replace with class where we want to avoid including Location.h
This commit is contained in:
Peter Barker 2023-02-03 09:58:39 +11:00 committed by Peter Barker
parent 034671b969
commit 5c262144f0
2 changed files with 11 additions and 11 deletions

View File

@ -40,9 +40,9 @@ static const struct {
Vector2f(-2.0f, 2.0f), true }, Vector2f(-2.0f, 2.0f), true },
}; };
static struct Location location_from_point(Vector2f pt) static Location location_from_point(Vector2f pt)
{ {
struct Location loc = {}; Location loc = {};
loc.lat = pt.x * 1.0e7f; loc.lat = pt.x * 1.0e7f;
loc.lng = pt.y * 1.0e7f; loc.lng = pt.y * 1.0e7f;
return loc; return loc;
@ -52,9 +52,9 @@ static void test_passed_waypoint(void)
{ {
hal.console->printf("waypoint tests starting\n"); hal.console->printf("waypoint tests starting\n");
for (uint8_t i = 0; i < ARRAY_SIZE(test_points); i++) { for (uint8_t i = 0; i < ARRAY_SIZE(test_points); i++) {
struct Location loc = location_from_point(test_points[i].location); Location loc = location_from_point(test_points[i].location);
struct Location wp1 = location_from_point(test_points[i].wp1); Location wp1 = location_from_point(test_points[i].wp1);
struct Location wp2 = location_from_point(test_points[i].wp2); Location wp2 = location_from_point(test_points[i].wp2);
if (loc.past_interval_finish_line(wp1, wp2) != test_points[i].passed) { if (loc.past_interval_finish_line(wp1, wp2) != test_points[i].passed) {
hal.console->printf("Failed waypoint test %u\n", (unsigned)i); hal.console->printf("Failed waypoint test %u\n", (unsigned)i);
return; return;
@ -63,11 +63,11 @@ static void test_passed_waypoint(void)
hal.console->printf("waypoint tests OK\n"); hal.console->printf("waypoint tests OK\n");
} }
static void test_one_offset(const struct Location &loc, static void test_one_offset(const Location &loc,
float ofs_north, float ofs_east, float ofs_north, float ofs_east,
float dist, float bearing) float dist, float bearing)
{ {
struct Location loc2; Location loc2;
float dist2, bearing2; float dist2, bearing2;
loc2 = loc; loc2 = loc;
@ -102,7 +102,7 @@ static const struct {
static void test_offset(void) static void test_offset(void)
{ {
struct Location loc {}; Location loc {};
loc.lat = -35 * 1.0e7f; loc.lat = -35 * 1.0e7f;
loc.lng = 149 * 1.0e7f; loc.lng = 149 * 1.0e7f;
@ -122,12 +122,12 @@ static void test_offset(void)
*/ */
static void test_accuracy(void) static void test_accuracy(void)
{ {
struct Location loc {}; Location loc {};
loc.lat = 0.0e7f; loc.lat = 0.0e7f;
loc.lng = -120.0e7f; loc.lng = -120.0e7f;
struct Location loc2 = loc; Location loc2 = loc;
Vector2f v((loc.lat * 1.0e-7f), (loc.lng* 1.0e-7f)); Vector2f v((loc.lat * 1.0e-7f), (loc.lng* 1.0e-7f));
Vector2f v2; Vector2f v2;

View File

@ -17,7 +17,7 @@
*/ */
/* /*
* this module deals with calculations involving struct Location * this module deals with calculations involving locations
*/ */
#include <stdlib.h> #include <stdlib.h>
#include "AP_Math.h" #include "AP_Math.h"