Merge pull request #1100 from PX4/warning_fixes_v3

Warning fixes v3
This commit is contained in:
Lorenz Meier 2014-06-30 16:33:53 +02:00
commit 3c5f35da73
22 changed files with 83 additions and 44 deletions

View File

@ -99,7 +99,7 @@
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init();
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
__END_DECLS

View File

@ -54,13 +54,13 @@
* CONFIG_ARCH_LEDS configuration switch.
*/
__BEGIN_DECLS
extern void led_init();
extern void led_init(void);
extern void led_on(int led);
extern void led_off(int led);
extern void led_toggle(int led);
__END_DECLS
__EXPORT void led_init()
__EXPORT void led_init(void)
{
/* Configure LED1-2 GPIOs for output */

View File

@ -131,6 +131,7 @@
#include <fcntl.h>
#include <sys/prctl.h>
#include <math.h>
#include <float.h>
#include <mathlib/mathlib.h>
#include <string.h>
#include <drivers/drv_hrt.h>
@ -526,7 +527,7 @@ int mat_invert3(float src[3][3], float dst[3][3])
src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) +
src[0][2] * (src[1][0] * src[2][1] - src[1][1] * src[2][0]);
if (det == 0.0f) {
if (fabsf(det) < FLT_EPSILON) {
return ERROR; // Singular matrix
}

View File

@ -40,6 +40,7 @@
*/
#include <math.h>
#include <float.h>
#include "calibration_routines.h"
@ -179,9 +180,9 @@ int sphere_fit_least_squares(const float x[], const float y[], const float z[],
aA = Q2 + 16.0f * (A2 - 2.0f * A * x_sum + x_sum2);
aB = Q2 + 16.0f * (B2 - 2.0f * B * y_sum + y_sum2);
aC = Q2 + 16.0f * (C2 - 2.0f * C * z_sum + z_sum2);
aA = (aA == 0.0f) ? 1.0f : aA;
aB = (aB == 0.0f) ? 1.0f : aB;
aC = (aC == 0.0f) ? 1.0f : aC;
aA = (fabsf(aA) < FLT_EPSILON) ? 1.0f : aA;
aB = (fabsf(aB) < FLT_EPSILON) ? 1.0f : aB;
aC = (fabsf(aC) < FLT_EPSILON) ? 1.0f : aC;
//Compute next iteration
nA = A - ((F2 + 16.0f * (B * XY + C * XZ + x_sum * (-A2 - Q0) + A * (x_sum2 + Q1 - C * z_sum - B * y_sum))) / aA);

View File

@ -373,16 +373,16 @@ void print_status()
static orb_advert_t status_pub;
transition_result_t arm_disarm(bool arm, const int mavlink_fd, const char *armedBy)
transition_result_t arm_disarm(bool arm, const int mavlink_fd_local, const char *armedBy)
{
transition_result_t arming_res = TRANSITION_NOT_CHANGED;
// Transition the armed state. By passing mavlink_fd to arming_state_transition it will
// output appropriate error messages if the state cannot transition.
arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, mavlink_fd);
arming_res = arming_state_transition(&status, &safety, arm ? ARMING_STATE_ARMED : ARMING_STATE_STANDBY, &armed, mavlink_fd_local);
if (arming_res == TRANSITION_CHANGED && mavlink_fd) {
mavlink_log_info(mavlink_fd, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
mavlink_log_info(mavlink_fd_local, "[cmd] %s by %s", arm ? "ARMED" : "DISARMED", armedBy);
} else if (arming_res == TRANSITION_DENIED) {
tune_negative(true);
@ -509,7 +509,14 @@ bool handle_command(struct vehicle_status_s *status, const struct safety_s *safe
cmd_result = VEHICLE_CMD_RESULT_ACCEPTED;
} else {
mavlink_log_info(mavlink_fd, "Unsupported OVERRIDE_GOTO: %f %f %f %f %f %f %f %f", cmd->param1, cmd->param2, cmd->param3, cmd->param4, cmd->param5, cmd->param6, cmd->param7);
mavlink_log_info(mavlink_fd, "Unsupported OVERRIDE_GOTO: %f %f %f %f %f %f %f %f",
(double)cmd->param1,
(double)cmd->param2,
(double)cmd->param3,
(double)cmd->param4,
(double)cmd->param5,
(double)cmd->param6,
(double)cmd->param7);
}
}
break;
@ -760,7 +767,6 @@ int commander_thread_main(int argc, char *argv[])
hrt_abstime last_idle_time = 0;
hrt_abstime start_time = 0;
hrt_abstime last_auto_state_valid = 0;
bool status_changed = true;
bool param_init_forced = true;
@ -875,6 +881,7 @@ int commander_thread_main(int argc, char *argv[])
bool arming_state_changed = false;
bool main_state_changed = false;
bool failsafe_old = false;
bool system_checked = false;
while (!thread_should_exit) {
@ -931,6 +938,15 @@ int commander_thread_main(int argc, char *argv[])
param_get(_param_enable_datalink_loss, &datalink_loss_enabled);
}
/* Perform system checks (again) once params are loaded and MAVLink is up. */
if (!system_checked && mavlink_fd &&
(telemetry.heartbeat_time > 0) &&
(hrt_elapsed_time(&telemetry.heartbeat_time) < 1 * 1000 * 1000)) {
(void)rc_calibration_check(mavlink_fd);
system_checked = true;
}
orb_check(sp_man_sub, &updated);
if (updated) {

View File

@ -474,7 +474,7 @@ Mavlink::get_instance_id()
return _instance_id;
}
const mavlink_channel_t
mavlink_channel_t
Mavlink::get_channel()
{
return _channel;
@ -2109,7 +2109,7 @@ Mavlink::task_main(int argc, char *argv[])
write_ptr = (uint8_t*)&msg;
// Pull a single message from the buffer
int read_count = available;
size_t read_count = available;
if (read_count > sizeof(mavlink_message_t)) {
read_count = sizeof(mavlink_message_t);
}

View File

@ -213,15 +213,15 @@ public:
*/
int enable_flow_control(bool enabled);
const mavlink_channel_t get_channel();
mavlink_channel_t get_channel();
void configure_stream_threadsafe(const char *stream_name, const float rate);
void configure_stream_threadsafe(const char *stream_name, float rate);
bool _task_should_exit; /**< if true, mavlink task should exit */
int get_mavlink_fd() { return _mavlink_fd; }
MavlinkStream * get_streams() { return _streams; } const
MavlinkStream * get_streams() const { return _streams; }
/* Functions for waiting to start transmission until message received. */
@ -311,15 +311,15 @@ private:
pthread_mutex_t _message_buffer_mutex;
perf_counter_t _loop_perf; /**< loop performance counter */
perf_counter_t _txerr_perf; /**< TX error counter */
bool _param_initialized;
param_t _param_system_id;
param_t _param_component_id;
param_t _param_system_type;
param_t _param_use_hil_gps;
perf_counter_t _loop_perf; /**< loop performance counter */
perf_counter_t _txerr_perf; /**< TX error counter */
/**
* Send one parameter.
*

View File

@ -44,10 +44,10 @@
#include "mavlink_main.h"
MavlinkStream::MavlinkStream() :
_last_sent(0),
next(nullptr),
_channel(MAVLINK_COMM_0),
_interval(1000000),
next(nullptr)
_last_sent(0)
{
}

View File

@ -42,6 +42,8 @@
#include <string.h>
#include <stdlib.h>
#include <unistd.h>
#include <math.h>
#include <float.h>
#include <systemlib/err.h>
#include <geo/geo.h>
@ -222,7 +224,7 @@ MissionBlock::set_loiter_item(struct position_setpoint_triplet_s *pos_sp_triplet
}
if (pos_sp_triplet->current.type != SETPOINT_TYPE_LOITER
|| pos_sp_triplet->current.loiter_radius != _navigator->get_loiter_radius()
|| (fabsf(pos_sp_triplet->current.loiter_radius - _navigator->get_loiter_radius()) > FLT_EPSILON)
|| pos_sp_triplet->current.loiter_direction != 1
|| pos_sp_triplet->previous.valid
|| !pos_sp_triplet->current.valid

View File

@ -227,7 +227,7 @@ RTL::set_rtl_item(position_setpoint_triplet_s *pos_sp_triplet)
_navigator->set_can_loiter_at_sp(true);
if (autoland) {
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: loiter %.1fs", _mission_item.time_inside);
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: loiter %.1fs", (double)_mission_item.time_inside);
} else {
mavlink_log_info(_navigator->get_mavlink_fd(), "#audio: RTL: completed, loiter");

View File

@ -49,6 +49,7 @@
#include <sys/prctl.h>
#include <termios.h>
#include <math.h>
#include <float.h>
#include <uORB/uORB.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/actuator_controls.h>
@ -477,7 +478,11 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float flow_dt = flow_prev > 0 ? (flow.flow_timestamp - flow_prev) * 1e-6f : 0.1f;
flow_prev = flow.flow_timestamp;
if (flow.ground_distance_m > 0.31f && flow.ground_distance_m < 4.0f && att.R[2][2] > 0.7f && flow.ground_distance_m != sonar_prev) {
if ((flow.ground_distance_m > 0.31f) &&
(flow.ground_distance_m < 4.0f) &&
(att.R[2][2] > 0.7f) &&
(fabsf(flow.ground_distance_m - sonar_prev) > FLT_EPSILON)) {
sonar_time = t;
sonar_prev = flow.ground_distance_m;
corr_sonar = flow.ground_distance_m + surface_offset + z_est[0];
@ -952,11 +957,11 @@ int position_estimator_inav_thread_main(int argc, char *argv[])
float updates_dt = (t - updates_counter_start) * 0.000001f;
warnx(
"updates rate: accelerometer = %.1f/s, baro = %.1f/s, gps = %.1f/s, attitude = %.1f/s, flow = %.1f/s",
accel_updates / updates_dt,
baro_updates / updates_dt,
gps_updates / updates_dt,
attitude_updates / updates_dt,
flow_updates / updates_dt);
(double)(accel_updates / updates_dt),
(double)(baro_updates / updates_dt),
(double)(gps_updates / updates_dt),
(double)(attitude_updates / updates_dt),
(double)(flow_updates / updates_dt));
updates_counter_start = t;
accel_updates = 0;
baro_updates = 0;

View File

@ -331,6 +331,7 @@ i2c_tx_complete(void)
i2c_tx_setup();
}
#ifdef DEBUG
static void
i2c_dump(void)
{
@ -339,3 +340,4 @@ i2c_dump(void)
debug("CCR 0x%08x TRISE 0x%08x", rCCR, rTRISE);
debug("SR1 0x%08x SR2 0x%08x", rSR1, rSR2);
}
#endif

View File

@ -119,13 +119,15 @@ sbus_init(const char *device)
bool
sbus1_output(uint16_t *values, uint16_t num_values)
{
write(sbus_fd, 'A', 1);
char a = 'A';
write(sbus_fd, &a, 1);
}
bool
sbus2_output(uint16_t *values, uint16_t num_values)
{
write(sbus_fd, 'B', 1);
char b = 'B';
write(sbus_fd, &b, 1);
}
bool

View File

@ -1315,7 +1315,7 @@ Sensors::adc_poll(struct sensor_combined_s &raw)
* a valid voltage from a connected sensor. Also assume a non-
* zero offset from the sensor if its connected.
*/
if (voltage > 0.4f && _parameters.diff_pres_analog_enabled) {
if (voltage > 0.4f && (_parameters.diff_pres_analog_enabled > 0)) {
float diff_pres_pa = voltage * 1000.0f - _parameters.diff_pres_offset_pa; //for MPXV7002DP sensor

View File

@ -42,6 +42,7 @@
#include <stdio.h>
#include <fcntl.h>
#include <systemlib/err.h>
#include <systemlib/rc_check.h>
#include <systemlib/param/param.h>
#include <mavlink/mavlink_log.h>

View File

@ -64,6 +64,9 @@ systemreset(bool to_bootloader)
*(uint32_t *)0x40002850 = 0xb007b007;
}
up_systemreset();
/* lock up here */
while(true);
}
static void kill_task(FAR struct tcb_s *tcb, FAR void *arg);

View File

@ -237,8 +237,10 @@ void at24c_test(void)
} else if (result != 1) {
vdbg("unexpected %u\n", result);
}
if ((count % 100) == 0)
if ((count % 100) == 0) {
vdbg("test %u errors %u\n", count, errors);
}
}
}

View File

@ -515,7 +515,8 @@ pwm_main(int argc, char *argv[])
ret = poll(&fds, 1, 0);
if (ret > 0) {
int ret = read(0, &c, 1);
ret = read(0, &c, 1);
if (ret > 0) {
/* reset output to the last value */
for (unsigned i = 0; i < servo_count; i++) {

View File

@ -65,7 +65,7 @@ int test_conv(int argc, char *argv[])
float f = i/10000.0f;
float fres = REG_TO_FLOAT(FLOAT_TO_REG(f));
if (fabsf(f - fres) > 0.0001f) {
warnx("conversion fail: input: %8.4f, intermediate: %d, result: %8.4f", f, REG_TO_SIGNED(FLOAT_TO_REG(f)), (double)fres);
warnx("conversion fail: input: %8.4f, intermediate: %d, result: %8.4f", (double)f, REG_TO_SIGNED(FLOAT_TO_REG(f)), (double)fres);
return 1;
}
}

View File

@ -149,6 +149,8 @@ test_file(int argc, char *argv[])
}
end = hrt_absolute_time();
warnx("write took %llu us", (end - start));
close(fd);
fd = open("/fs/microsd/testfile", O_RDONLY);
@ -192,7 +194,6 @@ test_file(int argc, char *argv[])
warnx("testing aligned writes - please wait.. (CTRL^C to abort)");
start = hrt_absolute_time();
for (unsigned i = 0; i < iterations; i++) {
int wret = write(fd, write_buf, chunk_sizes[c]);

View File

@ -68,7 +68,7 @@ int test_float(int argc, char *argv[])
float sinf_one = sinf(1.0f);
float sqrt_two = sqrt(2.0f);
if (sinf_zero == 0.0f) {
if (fabsf(sinf_zero) < FLT_EPSILON) {
printf("\t success: sinf(0.0f) == 0.0f\n");
} else {
@ -136,7 +136,7 @@ int test_float(int argc, char *argv[])
ret = -2;
}
if (sqrt_two == 1.41421356f) {
if (fabsf(sqrt_two - 1.41421356f) < FLT_EPSILON) {
printf("\t success: sqrt(2.0f) == 1.41421f\n");
} else {
@ -188,7 +188,7 @@ int test_float(int argc, char *argv[])
double d1d2 = d1 * d2;
if (d1d2 == 2.022200000000000219557705349871) {
if (fabs(d1d2 - 2.022200000000000219557705349871) < DBL_EPSILON) {
printf("\t success: 1.0111 * 2.0 == 2.0222\n");
} else {
@ -201,7 +201,7 @@ int test_float(int argc, char *argv[])
// Assign value of f1 to d1
d1 = f1;
if (f1 == (float)d1) {
if (fabsf(f1 - (float)d1) < FLT_EPSILON) {
printf("\t success: (float) 1.55f == 1.55 (double)\n");
} else {
@ -216,7 +216,7 @@ int test_float(int argc, char *argv[])
double sin_one = sin(1.0);
double atan2_ones = atan2(1.0, 1.0);
if (sin_zero == 0.0) {
if (fabs(sin_zero - 0.0) < DBL_EPSILON) {
printf("\t success: sin(0.0) == 0.0\n");
} else {
@ -224,7 +224,7 @@ int test_float(int argc, char *argv[])
ret = -9;
}
if (sin_one == 0.841470984807896504875657228695) {
if (fabs(sin_one - 0.841470984807896504875657228695) < DBL_EPSILON) {
printf("\t success: sin(1.0) == 0.84147098480\n");
} else {
@ -232,7 +232,7 @@ int test_float(int argc, char *argv[])
ret = -10;
}
if (atan2_ones != 0.785398) {
if (fabs(atan2_ones - 0.785398) < DBL_EPSILON) {
printf("\t success: atan2(1.0, 1.0) == 0.785398\n");
} else {

View File

@ -171,6 +171,8 @@ test_mtd(int argc, char *argv[])
}
end = hrt_absolute_time();
warnx("write took %llu us", (end - start));
close(fd);
fd = open(PARAM_FILE_NAME, O_RDONLY);