1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-20 23:05:19 +03:00

Added junittest XML test results.

This commit is contained in:
Anders Hoglund 2016-10-16 17:48:31 +02:00
parent c5042e2099
commit 15d9eaffd4
3 changed files with 39 additions and 9 deletions

View file

@ -41,7 +41,7 @@ extern "C" {
static void rotateVector(int32_t mat[3][3], int32_t vec[3], int32_t *out)
{
int16_t tmp[3];
int32_t tmp[3];
for(int i=0; i<3; i++) {
tmp[i] = 0;
@ -56,7 +56,7 @@ static void rotateVector(int32_t mat[3][3], int32_t vec[3], int32_t *out)
}
//static void initXAxisRotation(int32_t mat[][3], int16_t angle)
//static void initXAxisRotation(int32_t mat[][3], int32_t angle)
//{
// mat[0][0] = 1;
// mat[0][1] = 0;
@ -69,7 +69,7 @@ static void rotateVector(int32_t mat[3][3], int32_t vec[3], int32_t *out)
// mat[2][2] = cos(angle*DEG2RAD);
//}
static void initYAxisRotation(int32_t mat[][3], int16_t angle)
static void initYAxisRotation(int32_t mat[][3], int32_t angle)
{
mat[0][0] = cos(angle*DEG2RAD);
mat[0][1] = 0;
@ -82,7 +82,7 @@ static void initYAxisRotation(int32_t mat[][3], int16_t angle)
mat[2][2] = cos(angle*DEG2RAD);
}
static void initZAxisRotation(int32_t mat[][3], int16_t angle)
static void initZAxisRotation(int32_t mat[][3], int32_t angle)
{
mat[0][0] = cos(angle*DEG2RAD);
mat[0][1] = -sin(angle*DEG2RAD);
@ -95,7 +95,7 @@ static void initZAxisRotation(int32_t mat[][3], int16_t angle)
mat[2][2] = 1;
}
static void testCW(sensor_align_e rotation, int16_t angle)
static void testCW(sensor_align_e rotation, int32_t angle)
{
int32_t src[XYZ_AXIS_COUNT];
int32_t dest[XYZ_AXIS_COUNT];
@ -153,7 +153,7 @@ static void testCW(sensor_align_e rotation, int16_t angle)
* Since the order of flip and rotation matters, these tests make the
* assumption that the 'flip' occurs first, followed by clockwise rotation
*/
static void testCWFlip(sensor_align_e rotation, int16_t angle)
static void testCWFlip(sensor_align_e rotation, int32_t angle)
{
int32_t src[XYZ_AXIS_COUNT];
int32_t dest[XYZ_AXIS_COUNT];