mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-09 16:13:56 -03:00
AP_Math: Unify from print or println to printf.
This commit is contained in:
parent
2643e7e906
commit
ec4cce15a1
@ -84,14 +84,14 @@ void test_matrix_eulers(void)
|
|||||||
uint8_t i, j, k;
|
uint8_t i, j, k;
|
||||||
uint8_t N = ARRAY_SIZE(angles);
|
uint8_t N = ARRAY_SIZE(angles);
|
||||||
|
|
||||||
hal.console->println("rotation matrix unit tests\n");
|
hal.console->printf("rotation matrix unit tests\n\n");
|
||||||
|
|
||||||
for (i=0; i<N; i++)
|
for (i=0; i<N; i++)
|
||||||
for (j=0; j<N; j++)
|
for (j=0; j<N; j++)
|
||||||
for (k=0; k<N; k++)
|
for (k=0; k<N; k++)
|
||||||
test_euler(angles[i], angles[j], angles[k]);
|
test_euler(angles[i], angles[j], angles[k]);
|
||||||
|
|
||||||
hal.console->println("tests done\n");
|
hal.console->printf("tests done\n\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
static void test_quaternion(float roll, float pitch, float yaw)
|
static void test_quaternion(float roll, float pitch, float yaw)
|
||||||
@ -123,7 +123,7 @@ void test_quaternion_eulers(void)
|
|||||||
uint8_t i, j, k;
|
uint8_t i, j, k;
|
||||||
uint8_t N = ARRAY_SIZE(angles);
|
uint8_t N = ARRAY_SIZE(angles);
|
||||||
|
|
||||||
hal.console->println("quaternion unit tests\n");
|
hal.console->printf("quaternion unit tests\n\n");
|
||||||
|
|
||||||
test_quaternion(M_PI/4, 0, 0);
|
test_quaternion(M_PI/4, 0, 0);
|
||||||
test_quaternion(0, M_PI/4, 0);
|
test_quaternion(0, M_PI/4, 0);
|
||||||
@ -148,7 +148,7 @@ void test_quaternion_eulers(void)
|
|||||||
for (k=0; k<N; k++)
|
for (k=0; k<N; k++)
|
||||||
test_quaternion(angles[i], angles[j], angles[k]);
|
test_quaternion(angles[i], angles[j], angles[k]);
|
||||||
|
|
||||||
hal.console->println("tests done\n");
|
hal.console->printf("tests done\n\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@ -183,7 +183,7 @@ void test_conversions(void)
|
|||||||
uint8_t i, j, k;
|
uint8_t i, j, k;
|
||||||
uint8_t N = ARRAY_SIZE(angles);
|
uint8_t N = ARRAY_SIZE(angles);
|
||||||
|
|
||||||
hal.console->println("matrix/quaternion tests\n");
|
hal.console->printf("matrix/quaternion tests\n\n");
|
||||||
|
|
||||||
test_conversion(1, 1.1f, 1.2f);
|
test_conversion(1, 1.1f, 1.2f);
|
||||||
test_conversion(1, -1.1f, 1.2f);
|
test_conversion(1, -1.1f, 1.2f);
|
||||||
@ -196,7 +196,7 @@ void test_conversions(void)
|
|||||||
for (k=0; k<N; k++)
|
for (k=0; k<N; k++)
|
||||||
test_conversion(angles[i], angles[j], angles[k]);
|
test_conversion(angles[i], angles[j], angles[k]);
|
||||||
|
|
||||||
hal.console->println("tests done\n");
|
hal.console->printf("tests done\n\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
void test_frame_transforms(void)
|
void test_frame_transforms(void)
|
||||||
@ -205,7 +205,7 @@ void test_frame_transforms(void)
|
|||||||
Quaternion q;
|
Quaternion q;
|
||||||
Matrix3f m;
|
Matrix3f m;
|
||||||
|
|
||||||
hal.console->println("frame transform tests\n");
|
hal.console->printf("frame transform tests\n\n");
|
||||||
|
|
||||||
q.from_euler(ToRad(45), ToRad(45), ToRad(45));
|
q.from_euler(ToRad(45), ToRad(45), ToRad(45));
|
||||||
q.normalize();
|
q.normalize();
|
||||||
@ -285,7 +285,7 @@ void test_matrix_rotate(void)
|
|||||||
*/
|
*/
|
||||||
void setup(void)
|
void setup(void)
|
||||||
{
|
{
|
||||||
hal.console->println("euler unit tests\n");
|
hal.console->printf("euler unit tests\n\n");
|
||||||
|
|
||||||
test_conversion(0, M_PI, 0);
|
test_conversion(0, M_PI, 0);
|
||||||
|
|
||||||
|
@ -44,7 +44,7 @@ static struct Location location_from_point(Vector2f pt)
|
|||||||
|
|
||||||
static void test_passed_waypoint(void)
|
static void test_passed_waypoint(void)
|
||||||
{
|
{
|
||||||
hal.console->println("waypoint tests starting");
|
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);
|
struct Location loc = location_from_point(test_points[i].location);
|
||||||
struct Location wp1 = location_from_point(test_points[i].wp1);
|
struct Location wp1 = location_from_point(test_points[i].wp1);
|
||||||
@ -54,7 +54,7 @@ static void test_passed_waypoint(void)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hal.console->println("waypoint tests OK");
|
hal.console->printf("waypoint tests OK\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
static void test_one_offset(const struct Location &loc,
|
static void test_one_offset(const struct Location &loc,
|
||||||
|
@ -147,9 +147,9 @@ static void test_matrix_inverse(void)
|
|||||||
|
|
||||||
void setup(void)
|
void setup(void)
|
||||||
{
|
{
|
||||||
hal.console->println("Matrix Algebra test\n");
|
hal.console->printf("Matrix Algebra test\n\n");
|
||||||
test_matrix_inverse();
|
test_matrix_inverse();
|
||||||
hal.console->println("Matrix Algebra tests done\n");
|
hal.console->printf("Matrix Algebra tests done\n\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop(void) {}
|
void loop(void) {}
|
||||||
|
@ -63,15 +63,15 @@ void setup(void)
|
|||||||
bool all_passed = true;
|
bool all_passed = true;
|
||||||
uint32_t start_time;
|
uint32_t start_time;
|
||||||
|
|
||||||
hal.console->println("polygon unit tests\n");
|
hal.console->printf("polygon unit tests\n\n");
|
||||||
|
|
||||||
if (!Polygon_complete(OBC_boundary, ARRAY_SIZE(OBC_boundary))) {
|
if (!Polygon_complete(OBC_boundary, ARRAY_SIZE(OBC_boundary))) {
|
||||||
hal.console->println("OBC boundary is not complete!");
|
hal.console->printf("OBC boundary is not complete!\n");
|
||||||
all_passed = false;
|
all_passed = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (Polygon_complete(OBC_boundary, ARRAY_SIZE(OBC_boundary)-1)) {
|
if (Polygon_complete(OBC_boundary, ARRAY_SIZE(OBC_boundary)-1)) {
|
||||||
hal.console->println("Polygon_complete test failed");
|
hal.console->printf("Polygon_complete test failed\n");
|
||||||
all_passed = false;
|
all_passed = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -88,9 +88,9 @@ void setup(void)
|
|||||||
all_passed = false;
|
all_passed = false;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
hal.console->println(all_passed ? "TEST PASSED" : "TEST FAILED");
|
hal.console->printf("%s\n", all_passed ? "TEST PASSED" : "TEST FAILED");
|
||||||
|
|
||||||
hal.console->println("Speed test:");
|
hal.console->printf("Speed test:\n");
|
||||||
start_time = AP_HAL::micros();
|
start_time = AP_HAL::micros();
|
||||||
for (count=0; count<1000; count++) {
|
for (count=0; count<1000; count++) {
|
||||||
for (i=0; i<ARRAY_SIZE(test_points); i++) {
|
for (i=0; i<ARRAY_SIZE(test_points); i++) {
|
||||||
@ -104,7 +104,7 @@ void setup(void)
|
|||||||
}
|
}
|
||||||
hal.console->printf("%u usec/call\n", (unsigned)((AP_HAL::micros()
|
hal.console->printf("%u usec/call\n", (unsigned)((AP_HAL::micros()
|
||||||
- start_time)/(count*ARRAY_SIZE(test_points))));
|
- start_time)/(count*ARRAY_SIZE(test_points))));
|
||||||
hal.console->println(all_passed ? "ALL TESTS PASSED" : "TEST FAILED");
|
hal.console->printf("%s\n", all_passed ? "ALL TESTS PASSED" : "TEST FAILED");
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop(void){}
|
void loop(void){}
|
||||||
|
@ -22,7 +22,7 @@ static void test_rotation_accuracy(void)
|
|||||||
int16_t i;
|
int16_t i;
|
||||||
float rot_angle;
|
float rot_angle;
|
||||||
|
|
||||||
hal.console->println("\nRotation method accuracy:");
|
hal.console->printf("\nRotation method accuracy:\n");
|
||||||
|
|
||||||
// test roll
|
// test roll
|
||||||
for( i=0; i<90; i++ ) {
|
for( i=0; i<90; i++ ) {
|
||||||
@ -150,7 +150,7 @@ static void test_euler(enum Rotation rotation, float roll, float pitch, float ya
|
|||||||
|
|
||||||
static void test_rotate_inverse(void)
|
static void test_rotate_inverse(void)
|
||||||
{
|
{
|
||||||
hal.console->println("\nrotate inverse test(Vector (1,1,1)):");
|
hal.console->printf("\nrotate inverse test(Vector (1,1,1)):\n");
|
||||||
Vector3f vec(1.0f,1.0f,1.0f), cmp_vec(1.0f,1.0f,1.0f);
|
Vector3f vec(1.0f,1.0f,1.0f), cmp_vec(1.0f,1.0f,1.0f);
|
||||||
for (enum Rotation r=ROTATION_NONE;
|
for (enum Rotation r=ROTATION_NONE;
|
||||||
r<ROTATION_MAX;
|
r<ROTATION_MAX;
|
||||||
@ -170,7 +170,7 @@ static void test_rotate_inverse(void)
|
|||||||
}
|
}
|
||||||
static void test_eulers(void)
|
static void test_eulers(void)
|
||||||
{
|
{
|
||||||
hal.console->println("euler tests");
|
hal.console->printf("euler tests\n");
|
||||||
test_euler(ROTATION_NONE, 0, 0, 0);
|
test_euler(ROTATION_NONE, 0, 0, 0);
|
||||||
test_euler(ROTATION_YAW_45, 0, 0, 45);
|
test_euler(ROTATION_YAW_45, 0, 0, 45);
|
||||||
test_euler(ROTATION_YAW_90, 0, 0, 90);
|
test_euler(ROTATION_YAW_90, 0, 0, 90);
|
||||||
@ -231,7 +231,7 @@ static bool have_rotation(const Matrix3f &m)
|
|||||||
|
|
||||||
static void missing_rotations(void)
|
static void missing_rotations(void)
|
||||||
{
|
{
|
||||||
hal.console->println("testing for missing rotations");
|
hal.console->printf("testing for missing rotations\n");
|
||||||
uint16_t roll, pitch, yaw;
|
uint16_t roll, pitch, yaw;
|
||||||
for (yaw=0; yaw<360; yaw += 90)
|
for (yaw=0; yaw<360; yaw += 90)
|
||||||
for (pitch=0; pitch<360; pitch += 90)
|
for (pitch=0; pitch<360; pitch += 90)
|
||||||
@ -249,12 +249,12 @@ static void missing_rotations(void)
|
|||||||
*/
|
*/
|
||||||
void setup(void)
|
void setup(void)
|
||||||
{
|
{
|
||||||
hal.console->println("rotation unit tests\n");
|
hal.console->printf("rotation unit tests\n\n");
|
||||||
test_rotation_accuracy();
|
test_rotation_accuracy();
|
||||||
test_eulers();
|
test_eulers();
|
||||||
missing_rotations();
|
missing_rotations();
|
||||||
test_rotate_inverse();
|
test_rotate_inverse();
|
||||||
hal.console->println("rotation unit tests done\n");
|
hal.console->printf("rotation unit tests done\n\n");
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop(void) {}
|
void loop(void) {}
|
||||||
|
Loading…
Reference in New Issue
Block a user