double promotion warning fix or ignore per module

This commit is contained in:
Daniel Agar 2018-01-07 21:43:17 -05:00 committed by Lorenz Meier
parent 11d348ec4f
commit cf74166801
41 changed files with 93 additions and 75 deletions

View File

@ -335,10 +335,12 @@ function(px4_add_common_flags)
set(warnings
-Wall
-Wextra
-Werror
-Warray-bounds
-Wdisabled-optimization
-Werror
-Wextra
-Wdouble-promotion
-Wfatal-errors
-Wfloat-equal
-Wformat-security
@ -346,7 +348,7 @@ function(px4_add_common_flags)
-Wlogical-op
-Wmissing-declarations
-Wmissing-field-initializers
#-Wmissing-include-dirs # TODO: fix and enable
-Wpointer-arith
-Wshadow
-Wuninitialized
@ -354,7 +356,7 @@ function(px4_add_common_flags)
-Wunused-variable
-Wno-implicit-fallthrough # set appropriate level and update
-Wno-missing-include-dirs # TODO: fix and enable
-Wno-unused-parameter
)
@ -368,14 +370,12 @@ function(px4_add_common_flags)
-Wno-address-of-packed-member
-Wno-unknown-warning-option
-Wunused-but-set-variable
#-Wdouble-promotion # needs work first
)
endif()
else()
list(APPEND warnings
-Wunused-but-set-variable
-Wformat=1
-Wdouble-promotion
)
endif()

View File

@ -485,8 +485,8 @@ CameraTrigger::test()
{
struct vehicle_command_s cmd = {
.timestamp = hrt_absolute_time(),
.param5 = 1.0f,
.param6 = 0.0f,
.param5 = 1.0,
.param6 = 0.0,
.param1 = 0.0f,
.param2 = 0.0f,
.param3 = 0.0f,

View File

@ -53,7 +53,7 @@ static constexpr const char PATH_MS5525[] = "/dev/ms5525";
/* Measurement rate is 100Hz */
static constexpr unsigned MEAS_RATE = 100;
static constexpr float MEAS_DRIVER_FILTER_FREQ = 1.2f;
static constexpr uint64_t CONVERSION_INTERVAL = (1000000 / MEAS_RATE); /* microseconds */
static constexpr int64_t CONVERSION_INTERVAL = (1000000 / MEAS_RATE); /* microseconds */
class MS5525 : public Airspeed
{

View File

@ -467,7 +467,7 @@ TERARANGER::ioctl(device::file_t *filp, int cmd, unsigned long arg)
bool want_start = (_measure_ticks == 0);
/* convert hz to tick interval via microseconds */
unsigned ticks = USEC2TICK(1000000 / arg);
int ticks = USEC2TICK(1000000 / arg);
/* check against maximum rate */
if (ticks < USEC2TICK(TERARANGER_CONVERSION_INTERVAL)) {

View File

@ -63,8 +63,8 @@ int OutputMavlink::update(const ControlData *control_data)
{
vehicle_command_s vehicle_command = {
.timestamp = 0,
.param5 = 0.0f,
.param6 = 0.0f,
.param5 = 0.0,
.param6 = 0.0,
.param1 = 0.0f,
.param2 = 0.0f,
.param3 = 0.0f,

View File

@ -89,7 +89,7 @@ public:
}
matrix::Vector<Type, M> getStdDev()
{
return getVar().pow(0.5);
return getVar().pow(0.5f);
}
private:
// attributes

View File

@ -34,6 +34,7 @@ px4_add_module(
MODULE lib__controllib__controllib_test
MAIN controllib_test
COMPILE_FLAGS
-Wno-double-promotion # TODO: fix in Matrix library Vector::pow()
SRCS
controllib_test_main.cpp
DEPENDS

View File

@ -75,7 +75,7 @@ protected:
work_s _work;
bool _sensor_ok;
uint32_t _measure_ticks;
int _measure_ticks;
bool _collect_phase;
float _diff_pres_offset;

@ -1 +1 @@
Subproject commit 1cba257bac94ffe7c9b48fb9ff9de73c582d68d8
Subproject commit b26c2d62b80d6bee148fbfe01eb36809bfa721ea

View File

@ -41,6 +41,8 @@
#include <math.h>
#include <stdlib.h>
#include <px4_defines.h>
#include "test.hpp"
bool __EXPORT equal(float a, float b, float epsilon)
@ -106,7 +108,7 @@ void __EXPORT float2SigExp(
// FIXME - This code makes no sense when exp is an int
// FIXME - isnan and isinf not defined for QuRT
#ifndef __PX4_QURT
if (isnan(num) || isinf(num)) {
if (!PX4_ISFINITE(num)) {
sig = 0.0f;
exp = -99;
return;

View File

@ -1089,7 +1089,7 @@ param_export(int fd, bool only_unsaved)
break;
case PARAM_TYPE_FLOAT: {
const float f = s->val.f;
const double f = (double)s->val.f;
debug("exporting: %s (%d) size: %d val: %.3f", name, s->param, size, (double)f);

View File

@ -31,4 +31,4 @@
#
############################################################################
px4_add_library(pid pid.c)
px4_add_library(pid pid.cpp)

View File

@ -50,6 +50,7 @@
#include "pid.h"
#include <math.h>
#include <px4_defines.h>
#define SIGMA 0.000001f
@ -71,35 +72,35 @@ __EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float
{
int ret = 0;
if (isfinite(kp)) {
if (PX4_ISFINITE(kp)) {
pid->kp = kp;
} else {
ret = 1;
}
if (isfinite(ki)) {
if (PX4_ISFINITE(ki)) {
pid->ki = ki;
} else {
ret = 1;
}
if (isfinite(kd)) {
if (PX4_ISFINITE(kd)) {
pid->kd = kd;
} else {
ret = 1;
}
if (isfinite(integral_limit)) {
if (PX4_ISFINITE(integral_limit)) {
pid->integral_limit = integral_limit;
} else {
ret = 1;
}
if (isfinite(output_limit)) {
if (PX4_ISFINITE(output_limit)) {
pid->output_limit = output_limit;
} else {
@ -111,7 +112,7 @@ __EXPORT int pid_set_parameters(PID_t *pid, float kp, float ki, float kd, float
__EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, float dt)
{
if (!isfinite(sp) || !isfinite(val) || !isfinite(val_dot) || !isfinite(dt)) {
if (!PX4_ISFINITE(sp) || !PX4_ISFINITE(val) || !PX4_ISFINITE(val_dot) || !PX4_ISFINITE(dt)) {
return pid->last_output;
}
@ -136,7 +137,7 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
d = 0.0f;
}
if (!isfinite(d)) {
if (!PX4_ISFINITE(d)) {
d = 0.0f;
}
@ -148,7 +149,7 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
i = pid->integral + (error * dt);
/* check for saturation */
if (isfinite(i)) {
if (PX4_ISFINITE(i)) {
if ((pid->output_limit < SIGMA || (fabsf(output + (i * pid->ki)) <= pid->output_limit)) &&
fabsf(i) <= pid->integral_limit) {
/* not saturated, use new integral value */
@ -161,7 +162,7 @@ __EXPORT float pid_calculate(PID_t *pid, float sp, float val, float val_dot, flo
}
/* limit output */
if (isfinite(output)) {
if (PX4_ISFINITE(output)) {
if (pid->output_limit > SIGMA) {
if (output > pid->output_limit) {
output = pid->output_limit;

View File

@ -31,4 +31,4 @@
#
############################################################################
px4_add_library(pwm_limit pwm_limit.c)
px4_add_library(pwm_limit pwm_limit.cpp)

View File

@ -42,6 +42,7 @@
#include "pwm_limit.h"
#include <px4_defines.h>
#include <math.h>
#include <stdbool.h>
#include <drivers/drv_hrt.h>
@ -148,7 +149,7 @@ void pwm_limit_calc(const bool armed, const bool pre_armed, const unsigned num_c
float control_value = output[i];
/* check for invalid / disabled channels */
if (!isfinite(control_value)) {
if (!PX4_ISFINITE(control_value)) {
effective_pwm[i] = disarmed_pwm[i];
continue;
}
@ -198,7 +199,7 @@ void pwm_limit_calc(const bool armed, const bool pre_armed, const unsigned num_c
float control_value = output[i];
/* check for invalid / disabled channels */
if (!isfinite(control_value)) {
if (!PX4_ISFINITE(control_value)) {
effective_pwm[i] = disarmed_pwm[i];
continue;
}

View File

@ -386,8 +386,8 @@ int commander_main(int argc, char *argv[])
struct vehicle_command_s cmd = {
.timestamp = hrt_absolute_time(),
.param5 = NAN,
.param6 = NAN,
.param5 = (double)NAN,
.param6 = (double)NAN,
/* minimum pitch */
.param1 = NAN,
.param2 = NAN,
@ -417,8 +417,8 @@ int commander_main(int argc, char *argv[])
struct vehicle_command_s cmd = {
.timestamp = 0,
.param5 = NAN,
.param6 = NAN,
.param5 = (double)NAN,
.param6 = (double)NAN,
/* minimum pitch */
.param1 = NAN,
.param2 = NAN,
@ -440,8 +440,8 @@ int commander_main(int argc, char *argv[])
struct vehicle_command_s cmd = {
.timestamp = 0,
.param5 = NAN,
.param6 = NAN,
.param5 = (double)NAN,
.param6 = (double)NAN,
/* transition to the other mode */
.param1 = (float)((status.is_rotary_wing) ? vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW : vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC),
.param2 = NAN,
@ -511,8 +511,8 @@ int commander_main(int argc, char *argv[])
struct vehicle_command_s cmd = {
.timestamp = 0,
.param5 = 0.0f,
.param6 = 0.0f,
.param5 = 0.0,
.param6 = 0.0,
/* if the comparison matches for off (== 0) set 0.0f, 2.0f (on) else */
.param1 = strcmp(argv[2], "off") ? 2.0f : 0.0f, /* lockdown */
.param2 = 0.0f,

View File

@ -1031,7 +1031,7 @@ _ram_flash_flush()
return;
}
const size_t len = (dm_operations_data.ram_flash.data_end - dm_operations_data.ram_flash.data) + 1;
const ssize_t len = (dm_operations_data.ram_flash.data_end - dm_operations_data.ram_flash.data) + 1;
ret = up_progmem_write(k_dataman_flash_sector->address, dm_operations_data.ram_flash.data, len);
if (ret < len) {

View File

@ -263,8 +263,8 @@ int SendEvent::custom_command(int argc, char *argv[])
struct vehicle_command_s cmd = {
.timestamp = 0,
.param5 = (float)((accel_calib || calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : NAN),
.param6 = NAN,
.param5 = ((accel_calib || calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : (double)NAN),
.param6 = (double)NAN,
.param1 = (float)((gyro_calib || calib_all) ? vehicle_command_s::PREFLIGHT_CALIBRATION_TEMPERATURE_CALIBRATION : NAN),
.param2 = NAN,
.param3 = NAN,

View File

@ -158,7 +158,7 @@ int TemperatureCalibrationAccel::update_sensor_instance(PerSensorData &data, int
}
//update linear fit matrices
double relative_temperature = data.sensor_sample_filt[3] - data.ref_temp;
double relative_temperature = (double)data.sensor_sample_filt[3] - (double)data.ref_temp;
data.P[0].update(relative_temperature, (double)data.sensor_sample_filt[0]);
data.P[1].update(relative_temperature, (double)data.sensor_sample_filt[1]);
data.P[2].update(relative_temperature, (double)data.sensor_sample_filt[2]);

View File

@ -145,7 +145,7 @@ int TemperatureCalibrationBaro::update_sensor_instance(PerSensorData &data, int
}
//update linear fit matrices
double relative_temperature = data.sensor_sample_filt[1] - data.ref_temp;
double relative_temperature = (double)data.sensor_sample_filt[1] - (double)data.ref_temp;
data.P[0].update(relative_temperature, (double)data.sensor_sample_filt[0]);
return 1;

View File

@ -145,7 +145,7 @@ int TemperatureCalibrationGyro::update_sensor_instance(PerSensorData &data, int
}
//update linear fit matrices
double relative_temperature = data.sensor_sample_filt[3] - data.ref_temp;
double relative_temperature = (double)data.sensor_sample_filt[3] - (double)data.ref_temp;
data.P[0].update(relative_temperature, (double)data.sensor_sample_filt[0]);
data.P[1].update(relative_temperature, (double)data.sensor_sample_filt[1]);
data.P[2].update(relative_temperature, (double)data.sensor_sample_filt[2]);

View File

@ -172,7 +172,7 @@ private:
void update_VTV(double x)
{
double temp = 1.0f;
double temp = 1.0;
int8_t z;
for (unsigned i = 0; i < _forder; i++) {

View File

@ -510,7 +510,7 @@ FixedwingPositionControl::calculate_gndspeed_undershoot(const Vector2f &curr_pos
delta_altitude = pos_sp_curr.alt - pos_sp_prev.alt;
} else {
distance = get_distance_to_next_waypoint(curr_pos(0), curr_pos(1), pos_sp_curr.lat, pos_sp_curr.lon);
distance = get_distance_to_next_waypoint((double)curr_pos(0), (double)curr_pos(1), pos_sp_curr.lat, pos_sp_curr.lon);
delta_altitude = pos_sp_curr.alt - _global_pos.alt;
}
@ -1314,17 +1314,20 @@ FixedwingPositionControl::control_landing(const Vector2f &curr_pos, const Vector
_fw_pos_ctrl_status.abort_landing = false;
}
const float bearing_airplane_currwp = get_bearing_to_next_waypoint(curr_pos(0), curr_pos(1), curr_wp(0), curr_wp(1));
const float bearing_airplane_currwp = get_bearing_to_next_waypoint((double)curr_pos(0), (double)curr_pos(1),
(double)curr_wp(0), (double)curr_wp(1));
float bearing_lastwp_currwp = bearing_airplane_currwp;
if (pos_sp_prev.valid) {
bearing_lastwp_currwp = get_bearing_to_next_waypoint(prev_wp(0), prev_wp(1), curr_wp(0), curr_wp(1));
bearing_lastwp_currwp = get_bearing_to_next_waypoint((double)prev_wp(0), (double)prev_wp(1), (double)curr_wp(0),
(double)curr_wp(1));
}
/* Horizontal landing control */
/* switch to heading hold for the last meters, continue heading hold after */
float wp_distance = get_distance_to_next_waypoint(curr_pos(0), curr_pos(1), curr_wp(0), curr_wp(1));
float wp_distance = get_distance_to_next_waypoint((double)curr_pos(0), (double)curr_pos(1), (double)curr_wp(0),
(double)curr_wp(1));
/* calculate a waypoint distance value which is 0 when the aircraft is behind the waypoint */
float wp_distance_save = wp_distance;
@ -1755,7 +1758,8 @@ FixedwingPositionControl::run()
Vector2f curr_wp((float)_pos_sp_triplet.current.lat, (float)_pos_sp_triplet.current.lon);
_fw_pos_ctrl_status.wp_dist = get_distance_to_next_waypoint(curr_pos(0), curr_pos(1), curr_wp(0), curr_wp(1));
_fw_pos_ctrl_status.wp_dist = get_distance_to_next_waypoint((double)curr_pos(0), (double)curr_pos(1),
(double)curr_wp(0), (double)curr_wp(1));
fw_pos_ctrl_status_publish();
}

View File

@ -461,8 +461,8 @@ GroundRoverPositionControl::task_main()
_gnd_pos_ctrl_status.xtrack_error = _gnd_control.crosstrack_error();
matrix::Vector2f curr_wp((float)_pos_sp_triplet.current.lat, (float)_pos_sp_triplet.current.lon);
_gnd_pos_ctrl_status.wp_dist = get_distance_to_next_waypoint(current_position(0), current_position(1), curr_wp(0),
curr_wp(1));
_gnd_pos_ctrl_status.wp_dist = get_distance_to_next_waypoint((double)current_position(0), (double)current_position(1),
(double)curr_wp(0), (double)curr_wp(1));
gnd_pos_ctrl_status_publish();
}

View File

@ -336,8 +336,8 @@ void BlockLocalPositionEstimator::update()
// if we have no lat, lon initialize projection to LPE_LAT, LPE_LON parameters
if (!_map_ref.init_done && (_estimatorInitialized & EST_XY) && _fake_origin.get()) {
map_projection_init(&_map_ref,
_init_origin_lat.get(),
_init_origin_lon.get());
(double)_init_origin_lat.get(),
(double)_init_origin_lon.get());
// set timestamp when origin was set to current time
_time_origin = _timeStamp;

View File

@ -35,6 +35,7 @@ px4_add_module(
MAIN local_position_estimator
COMPILE_FLAGS
-Wno-sign-compare # TODO: fix all sign-compare
-Wno-double-promotion # TODO: fix in Matrix library Vector::pow()
STACK_MAIN 5700
STACK_MAX 13000
SRCS

View File

@ -95,9 +95,9 @@ int BlockLocalPositionEstimator::gpsMeasure(Vector<double, n_y_gps> &y)
y(0) = _sub_gps.get().lat * 1e-7;
y(1) = _sub_gps.get().lon * 1e-7;
y(2) = _sub_gps.get().alt * 1e-3;
y(3) = _sub_gps.get().vel_n_m_s;
y(4) = _sub_gps.get().vel_e_m_s;
y(5) = _sub_gps.get().vel_d_m_s;
y(3) = (double)_sub_gps.get().vel_n_m_s;
y(4) = (double)_sub_gps.get().vel_e_m_s;
y(5) = (double)_sub_gps.get().vel_d_m_s;
// increament sums for mean
_gpsStats.update(y);

View File

@ -1561,8 +1561,8 @@ protected:
struct vehicle_command_s cmd = {
.timestamp = 0,
.param5 = NAN,
.param6 = NAN,
.param5 = (double)NAN,
.param6 = (double)NAN,
.param1 = 0.0f, // all cameras
.param2 = 0.0f, // duration 0 because only taking one picture
.param3 = 1.0f, // only take one

View File

@ -487,8 +487,8 @@ MavlinkReceiver::handle_message_command_long(mavlink_message_t *msg)
struct vehicle_command_s vcmd = {
.timestamp = hrt_absolute_time(),
.param5 = cmd_mavlink.param5,
.param6 = cmd_mavlink.param6,
.param5 = (double)cmd_mavlink.param5,
.param6 = (double)cmd_mavlink.param6,
/* Copy the content of mavlink_command_long_t cmd_mavlink into command_t cmd */
.param1 = cmd_mavlink.param1,
.param2 = cmd_mavlink.param2,

View File

@ -107,10 +107,10 @@ MavlinkTimesync::handle_message(const mavlink_message_t *msg)
// Filter gain scheduling
if (!sync_converged()) {
// Interpolate with a sigmoid function
float progress = ((float)_sequence) / CONVERGENCE_WINDOW;
float p = 1.0f - expf(0.5f * (1.0f - 1.0f / (1.0f - progress)));
_filter_alpha = p * (float)ALPHA_GAIN_FINAL + (1.0f - p) * (float)ALPHA_GAIN_INITIAL;
_filter_beta = p * (float)BETA_GAIN_FINAL + (1.0f - p) * (float)BETA_GAIN_INITIAL;
double progress = _sequence / CONVERGENCE_WINDOW;
double p = 1.0 - exp(0.5 * (1.0 - 1.0 / (1.0 - progress)));
_filter_alpha = p * ALPHA_GAIN_FINAL + (1.0 - p) * ALPHA_GAIN_INITIAL;
_filter_beta = p * BETA_GAIN_FINAL + (1.0 - p) * BETA_GAIN_INITIAL;
} else {
_filter_alpha = ALPHA_GAIN_FINAL;

View File

@ -229,7 +229,7 @@ bool Geofence::checkAll(double lat, double lon, float altitude)
const double home_lat = _navigator->get_home_position()->lat;
const double home_lon = _navigator->get_home_position()->lon;
const double home_alt = _navigator->get_home_position()->alt;
const float home_alt = _navigator->get_home_position()->alt;
float dist_xy = -1.0f;
float dist_z = -1.0f;

View File

@ -452,8 +452,8 @@ MissionBlock::issue_command(const mission_item_s &item)
vcmd.param2 = item.params[1];
vcmd.param3 = item.params[2];
vcmd.param4 = item.params[3];
vcmd.param5 = item.params[4];
vcmd.param6 = item.params[5];
vcmd.param5 = (double)item.params[4];
vcmd.param6 = (double)item.params[5];
if (item.nav_cmd == NAV_CMD_DO_SET_ROI_LOCATION && item.altitude_is_relative) {
vcmd.param7 = item.params[6] + _navigator->get_home_position()->alt;
@ -644,8 +644,8 @@ MissionBlock::set_land_item(struct mission_item_s *item, bool at_current_locatio
/* use current position */
if (at_current_location) {
item->lat = NAN; //descend at current position
item->lon = NAN; //descend at current position
item->lat = (double)NAN; //descend at current position
item->lon = (double)NAN; //descend at current position
item->yaw = _navigator->get_local_position()->yaw;
} else {

View File

@ -522,8 +522,8 @@ MissionFeasibilityChecker::checkDistancesBetweenWaypoints(const mission_s &missi
return true;
}
double last_lat = NAN;
double last_lon = NAN;
double last_lat = (double)NAN;
double last_lon = (double)NAN;
/* Go through all waypoints */
for (size_t i = 0; i < mission.count; i++) {

View File

@ -407,8 +407,8 @@ Navigator::run()
} else {
// If one of them is non-finite, reset both
rep->current.lat = NAN;
rep->current.lon = NAN;
rep->current.lat = (double)NAN;
rep->current.lon = (double)NAN;
}
rep->current.alt = cmd.param7;

View File

@ -59,6 +59,7 @@ px4_add_module(
MODULE modules__simulator
MAIN simulator
COMPILE_FLAGS
-Wno-double-promotion
INCLUDES
${PX4_SOURCE_DIR}/mavlink/include/mavlink
SRCS

View File

@ -34,6 +34,8 @@
px4_add_module(
MODULE drivers__accelsim
MAIN accelsim
COMPILE_FLAGS
-Wno-double-promotion
SRCS
accelsim.cpp
DEPENDS

View File

@ -35,6 +35,7 @@ px4_add_module(
MODULE drivers__airspeedsim
MAIN measairspeedsim
COMPILE_FLAGS
-Wno-double-promotion
SRCS
airspeedsim.cpp
meas_airspeed_sim.cpp

View File

@ -35,6 +35,7 @@ px4_add_module(
MODULE drivers__barosim
MAIN barosim
COMPILE_FLAGS
-Wno-double-promotion
SRCS
baro.cpp
DEPENDS

View File

@ -35,6 +35,7 @@ px4_add_module(
MODULE drivers__gpssim
MAIN gpssim
COMPILE_FLAGS
-Wno-double-promotion
SRCS
gpssim.cpp
DEPENDS

View File

@ -34,6 +34,8 @@
px4_add_module(
MODULE drivers__gyrosim
MAIN gyrosim
COMPILE_FLAGS
-Wno-double-promotion
STACK_MAIN 1200
SRCS
gyrosim.cpp

View File

@ -138,7 +138,7 @@ void print_load(uint64_t t, int fd, struct print_load_s *print_state)
clear_line,
th_cnt);
for (int j = 0; j < th_cnt; j++) {
for (unsigned j = 0; j < th_cnt; j++) {
thread_info_count = THREAD_INFO_MAX;
kr = thread_info(thread_list[j], THREAD_BASIC_INFO,
(thread_info_t)th_info_data, &thread_info_count);