From a5ffadf20137ce918777877efaddcba3271a5db6 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Fri, 24 Apr 2015 12:51:54 +0900 Subject: [PATCH] AP_Motors: fix compile warnings re float constants --- libraries/AP_Motors/AP_MotorsOcta.cpp | 32 +++++++++++------------ libraries/AP_Motors/AP_MotorsOctaQuad.cpp | 16 ++++++------ libraries/AP_Motors/AP_MotorsQuad.cpp | 8 +++--- libraries/AP_Motors/AP_MotorsY6.cpp | 24 ++++++++--------- libraries/AP_Motors/AP_Motors_Class.cpp | 2 +- 5 files changed, 41 insertions(+), 41 deletions(-) diff --git a/libraries/AP_Motors/AP_MotorsOcta.cpp b/libraries/AP_Motors/AP_MotorsOcta.cpp index b82c0b91c1..2fdb1e1861 100644 --- a/libraries/AP_Motors/AP_MotorsOcta.cpp +++ b/libraries/AP_Motors/AP_MotorsOcta.cpp @@ -42,24 +42,24 @@ void AP_MotorsOcta::setup_motors() }else if( _flags.frame_orientation == AP_MOTORS_V_FRAME ) { // V frame set-up - add_motor_raw(AP_MOTORS_MOT_1, 1.0, 0.34, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7); - add_motor_raw(AP_MOTORS_MOT_2, -1.0, -0.32, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); - add_motor_raw(AP_MOTORS_MOT_3, 1.0, -0.32, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); - add_motor_raw(AP_MOTORS_MOT_4, -0.5, -1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); - add_motor_raw(AP_MOTORS_MOT_5, 1.0, 1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8); - add_motor_raw(AP_MOTORS_MOT_6, -1.0, 0.34, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); - add_motor_raw(AP_MOTORS_MOT_7, -1.0, 1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); - add_motor_raw(AP_MOTORS_MOT_8, 0.5, -1.0, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); + add_motor_raw(AP_MOTORS_MOT_1, 1.0f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7); + add_motor_raw(AP_MOTORS_MOT_2, -1.0f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); + add_motor_raw(AP_MOTORS_MOT_3, 1.0f, -0.32f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); + add_motor_raw(AP_MOTORS_MOT_4, -0.5f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); + add_motor_raw(AP_MOTORS_MOT_5, 1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8); + add_motor_raw(AP_MOTORS_MOT_6, -1.0f, 0.34f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); + add_motor_raw(AP_MOTORS_MOT_7, -1.0f, 1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); + add_motor_raw(AP_MOTORS_MOT_8, 0.5f, -1.0f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); }else { // X frame set-up - add_motor(AP_MOTORS_MOT_1, 22.5, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); - add_motor(AP_MOTORS_MOT_2, -157.5, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); - add_motor(AP_MOTORS_MOT_3, 67.5, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); - add_motor(AP_MOTORS_MOT_4, 157.5, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); - add_motor(AP_MOTORS_MOT_5, -22.5, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8); - add_motor(AP_MOTORS_MOT_6, -112.5, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); - add_motor(AP_MOTORS_MOT_7, -67.5, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7); - add_motor(AP_MOTORS_MOT_8, 112.5, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); + add_motor(AP_MOTORS_MOT_1, 22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); + add_motor(AP_MOTORS_MOT_2, -157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); + add_motor(AP_MOTORS_MOT_3, 67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); + add_motor(AP_MOTORS_MOT_4, 157.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); + add_motor(AP_MOTORS_MOT_5, -22.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 8); + add_motor(AP_MOTORS_MOT_6, -112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); + add_motor(AP_MOTORS_MOT_7, -67.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 7); + add_motor(AP_MOTORS_MOT_8, 112.5f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); } } diff --git a/libraries/AP_Motors/AP_MotorsOctaQuad.cpp b/libraries/AP_Motors/AP_MotorsOctaQuad.cpp index 1f352a68df..c3492739db 100644 --- a/libraries/AP_Motors/AP_MotorsOctaQuad.cpp +++ b/libraries/AP_Motors/AP_MotorsOctaQuad.cpp @@ -41,14 +41,14 @@ void AP_MotorsOctaQuad::setup_motors() add_motor(AP_MOTORS_MOT_8, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 6); }else if( _flags.frame_orientation == AP_MOTORS_V_FRAME ) { // V frame set-up - add_motor(AP_MOTORS_MOT_1, 45, 0.7981, 1); - add_motor(AP_MOTORS_MOT_2, -45, -0.7981, 7); - add_motor(AP_MOTORS_MOT_3, -135, 1.0000, 5); - add_motor(AP_MOTORS_MOT_4, 135, -1.0000, 3); - add_motor(AP_MOTORS_MOT_5, -45, 0.7981, 8); - add_motor(AP_MOTORS_MOT_6, 45, -0.7981, 2); - add_motor(AP_MOTORS_MOT_7, 135, 1.0000, 4); - add_motor(AP_MOTORS_MOT_8, -135, -1.0000, 6); + add_motor(AP_MOTORS_MOT_1, 45, 0.7981f, 1); + add_motor(AP_MOTORS_MOT_2, -45, -0.7981f, 7); + add_motor(AP_MOTORS_MOT_3, -135, 1.0000f, 5); + add_motor(AP_MOTORS_MOT_4, 135, -1.0000f, 3); + add_motor(AP_MOTORS_MOT_5, -45, 0.7981f, 8); + add_motor(AP_MOTORS_MOT_6, 45, -0.7981f, 2); + add_motor(AP_MOTORS_MOT_7, 135, 1.0000f, 4); + add_motor(AP_MOTORS_MOT_8, -135, -1.0000f, 6); }else if( _flags.frame_orientation == AP_MOTORS_H_FRAME ) { // H frame set-up - same as X but motors spin in opposite directions add_motor(AP_MOTORS_MOT_1, 45, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); diff --git a/libraries/AP_Motors/AP_MotorsQuad.cpp b/libraries/AP_Motors/AP_MotorsQuad.cpp index 81ad765601..cd92f2997a 100644 --- a/libraries/AP_Motors/AP_MotorsQuad.cpp +++ b/libraries/AP_Motors/AP_MotorsQuad.cpp @@ -38,10 +38,10 @@ void AP_MotorsQuad::setup_motors() }else if( _flags.frame_orientation == AP_MOTORS_V_FRAME ) { // V frame set-up - add_motor(AP_MOTORS_MOT_1, 45, 0.7981, 1); - add_motor(AP_MOTORS_MOT_2, -135, 1.0000, 3); - add_motor(AP_MOTORS_MOT_3, -45, -0.7981, 4); - add_motor(AP_MOTORS_MOT_4, 135, -1.0000, 2); + add_motor(AP_MOTORS_MOT_1, 45, 0.7981f, 1); + add_motor(AP_MOTORS_MOT_2, -135, 1.0000f, 3); + add_motor(AP_MOTORS_MOT_3, -45, -0.7981f, 4); + add_motor(AP_MOTORS_MOT_4, 135, -1.0000f, 2); }else if( _flags.frame_orientation == AP_MOTORS_H_FRAME ) { // H frame set-up - same as X but motors spin in opposite directiSons diff --git a/libraries/AP_Motors/AP_MotorsY6.cpp b/libraries/AP_Motors/AP_MotorsY6.cpp index 37cb9a8117..08237144cb 100644 --- a/libraries/AP_Motors/AP_MotorsY6.cpp +++ b/libraries/AP_Motors/AP_MotorsY6.cpp @@ -30,19 +30,19 @@ void AP_MotorsY6::setup_motors() if (_flags.frame_orientation >= AP_MOTORS_NEW_PLUS_FRAME) { // Y6 motor definition with all top motors spinning clockwise, all bottom motors counter clockwise - add_motor_raw(AP_MOTORS_MOT_1, -1.0, 0.500, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); - add_motor_raw(AP_MOTORS_MOT_2, -1.0, 0.500, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); - add_motor_raw(AP_MOTORS_MOT_3, 0.0, -1.000, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); - add_motor_raw(AP_MOTORS_MOT_4, 0.0, -1.000, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); - add_motor_raw(AP_MOTORS_MOT_5, 1.0, 0.500, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); - add_motor_raw(AP_MOTORS_MOT_6, 1.0, 0.500, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); + add_motor_raw(AP_MOTORS_MOT_1, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); + add_motor_raw(AP_MOTORS_MOT_2, -1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); + add_motor_raw(AP_MOTORS_MOT_3, 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 3); + add_motor_raw(AP_MOTORS_MOT_4, 0.0f, -1.000f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4); + add_motor_raw(AP_MOTORS_MOT_5, 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); + add_motor_raw(AP_MOTORS_MOT_6, 1.0f, 0.500f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); }else{ // original Y6 motor definition - add_motor_raw(AP_MOTORS_MOT_1, -1.0, 0.666, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); - add_motor_raw(AP_MOTORS_MOT_2, 1.0, 0.666, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); - add_motor_raw(AP_MOTORS_MOT_3, 1.0, 0.666, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); - add_motor_raw(AP_MOTORS_MOT_4, 0.0, -1.333, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4); - add_motor_raw(AP_MOTORS_MOT_5, -1.0, 0.666, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); - add_motor_raw(AP_MOTORS_MOT_6, 0.0, -1.333, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3); + add_motor_raw(AP_MOTORS_MOT_1, -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2); + add_motor_raw(AP_MOTORS_MOT_2, 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 5); + add_motor_raw(AP_MOTORS_MOT_3, 1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 6); + add_motor_raw(AP_MOTORS_MOT_4, 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 4); + add_motor_raw(AP_MOTORS_MOT_5, -1.0f, 0.666f, AP_MOTORS_MATRIX_YAW_FACTOR_CW, 1); + add_motor_raw(AP_MOTORS_MOT_6, 0.0f, -1.333f, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3); } } diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index de46864243..004f3e4165 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -302,7 +302,7 @@ void AP_Motors::update_lift_max_from_batt_voltage() { // sanity check battery_voltage_min is not too small // if disabled or misconfigured exit immediately - if((_batt_voltage_max <= 0) || (_batt_voltage_min >= _batt_voltage_max) || (_batt_voltage < 0.25*_batt_voltage_min)) { + if((_batt_voltage_max <= 0) || (_batt_voltage_min >= _batt_voltage_max) || (_batt_voltage < 0.25f*_batt_voltage_min)) { _batt_voltage_filt.reset(1.0f); _lift_max = 1.0f; return;