mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-28 02:33:58 -04:00
AP_Math: compiler warnings: float to double
This commit is contained in:
parent
d09ef4783d
commit
a5d2f3a82f
@ -268,7 +268,7 @@ void test_frame_transforms(void)
|
||||
static float rand_num(void)
|
||||
{
|
||||
float ret = ((unsigned)random()) % 2000000;
|
||||
return (ret - 1.0e6) / 1.0e6;
|
||||
return (ret - 1.0e6f) / 1.0e6f;
|
||||
}
|
||||
|
||||
void test_matrix_rotate(void)
|
||||
|
@ -69,8 +69,8 @@ static const struct {
|
||||
static struct Location location_from_point(Vector2f pt)
|
||||
{
|
||||
struct Location loc = {0};
|
||||
loc.lat = pt.x * 1.0e7;
|
||||
loc.lng = pt.y * 1.0e7;
|
||||
loc.lat = pt.x * 1.0e7f;
|
||||
loc.lng = pt.y * 1.0e7f;
|
||||
return loc;
|
||||
}
|
||||
|
||||
@ -130,8 +130,8 @@ static void test_offset(void)
|
||||
{
|
||||
struct Location loc;
|
||||
|
||||
loc.lat = -35*1.0e7;
|
||||
loc.lng = 149*1.0e7;
|
||||
loc.lat = -35*1.0e7f;
|
||||
loc.lng = 149*1.0e7f;
|
||||
|
||||
for (uint8_t i=0; i<ARRAY_LENGTH(test_offsets); i++) {
|
||||
test_one_offset(loc,
|
||||
|
@ -89,8 +89,8 @@ void setup(void)
|
||||
result = Polygon_outside(test_points[i].point,
|
||||
OBC_boundary, ARRAY_LENGTH(OBC_boundary));
|
||||
hal.console->printf_P(PSTR("%10f,%10f %s %s\n"),
|
||||
1.0e-7*test_points[i].point.x,
|
||||
1.0e-7*test_points[i].point.y,
|
||||
1.0e-7f*test_points[i].point.x,
|
||||
1.0e-7f*test_points[i].point.y,
|
||||
result ? "OUTSIDE" : "INSIDE ",
|
||||
result == test_points[i].outside ? "PASS" : "FAIL");
|
||||
if (result != test_points[i].outside) {
|
||||
|
@ -81,7 +81,7 @@ static void test_euler(enum Rotation rotation, float roll, float pitch, float ya
|
||||
{
|
||||
Vector3f v, v1, v2, diff;
|
||||
Matrix3f rotmat;
|
||||
const float accuracy = 1.0e-6;
|
||||
const float accuracy = 1.0e-6f;
|
||||
|
||||
v.x = 1;
|
||||
v.y = 2;
|
||||
|
Loading…
Reference in New Issue
Block a user