mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-21 21:55:34 +08:00
fix all sign-compare warnings
This commit is contained in:
committed by
Lorenz Meier
parent
cf74166801
commit
9ce83f2208
@@ -34,7 +34,6 @@ px4_add_module(
|
||||
MODULE drivers__mb12xx
|
||||
MAIN mb12xx
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare
|
||||
SRCS
|
||||
mb12xx.cpp
|
||||
DEPENDS
|
||||
|
||||
@@ -118,9 +118,9 @@ private:
|
||||
float _min_distance;
|
||||
float _max_distance;
|
||||
work_s _work;
|
||||
ringbuffer::RingBuffer *_reports;
|
||||
ringbuffer::RingBuffer *_reports;
|
||||
bool _sensor_ok;
|
||||
int _measure_ticks;
|
||||
int _measure_ticks;
|
||||
bool _collect_phase;
|
||||
int _class_instance;
|
||||
int _orb_class_instance;
|
||||
|
||||
@@ -34,7 +34,6 @@ px4_add_module(
|
||||
MODULE drivers__sf0x
|
||||
MAIN sf0x
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare # TODO: fix all sign-compare
|
||||
SRCS
|
||||
sf0x.cpp
|
||||
sf0x_parser.cpp
|
||||
|
||||
@@ -105,7 +105,7 @@ private:
|
||||
uint8_t _rotation;
|
||||
float _min_distance;
|
||||
float _max_distance;
|
||||
int _conversion_interval;
|
||||
int _conversion_interval;
|
||||
work_s _work;
|
||||
ringbuffer::RingBuffer *_reports;
|
||||
int _measure_ticks;
|
||||
@@ -419,7 +419,7 @@ SF0X::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(_conversion_interval)) {
|
||||
@@ -564,7 +564,7 @@ SF0X::collect()
|
||||
perf_begin(_sample_perf);
|
||||
|
||||
/* clear buffer if last read was too long ago */
|
||||
uint64_t read_elapsed = hrt_elapsed_time(&_last_read);
|
||||
int64_t read_elapsed = hrt_elapsed_time(&_last_read);
|
||||
|
||||
/* the buffer for read chars is buflen minus null termination */
|
||||
char readbuf[sizeof(_linebuf)];
|
||||
|
||||
@@ -34,7 +34,6 @@ px4_add_module(
|
||||
MODULE drivers__sf0x__sf0x_tests
|
||||
MAIN sf0x_tests
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare # TODO: fix all sign-compare
|
||||
SRCS
|
||||
SF0XTest.cpp
|
||||
../sf0x_parser.cpp
|
||||
|
||||
@@ -58,9 +58,9 @@ bool SF0XTest::sf0xTest()
|
||||
for (unsigned l = 0; l < sizeof(lines) / sizeof(lines[0]); l++) {
|
||||
//printf("\n%s", _linebuf);
|
||||
|
||||
int parse_ret;
|
||||
int parse_ret = -1;
|
||||
|
||||
for (int i = 0; i < strlen(lines[l]); i++) {
|
||||
for (int i = 0; i < (ssize_t)strlen(lines[l]); i++) {
|
||||
parse_ret = sf0x_parser(lines[l][i], _parserbuf, &_parsebuf_index, &state, &dist_m);
|
||||
|
||||
if (parse_ret == 0) {
|
||||
|
||||
@@ -35,7 +35,6 @@ px4_add_module(
|
||||
MODULE drivers__sf1xx
|
||||
MAIN sf1xx
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare
|
||||
SRCS
|
||||
sf1xx.cpp
|
||||
DEPENDS
|
||||
|
||||
@@ -34,7 +34,6 @@ px4_add_module(
|
||||
MODULE drivers__srf02
|
||||
MAIN srf02
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare
|
||||
SRCS
|
||||
srf02.cpp
|
||||
DEPENDS
|
||||
|
||||
@@ -35,7 +35,6 @@ px4_add_module(
|
||||
MAIN teraranger
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare
|
||||
SRCS
|
||||
teraranger.cpp
|
||||
DEPENDS
|
||||
|
||||
@@ -125,7 +125,7 @@ private:
|
||||
ringbuffer::RingBuffer *_reports;
|
||||
bool _sensor_ok;
|
||||
uint8_t _valid;
|
||||
int _measure_ticks;
|
||||
int _measure_ticks;
|
||||
bool _collect_phase;
|
||||
int _class_instance;
|
||||
int _orb_class_instance;
|
||||
|
||||
@@ -34,7 +34,6 @@ px4_add_module(
|
||||
MODULE drivers__tfmini
|
||||
MAIN tfmini
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare
|
||||
SRCS
|
||||
tfmini.cpp
|
||||
tfmini_parser.cpp
|
||||
|
||||
@@ -411,7 +411,7 @@ TFMINI::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(_conversion_interval)) {
|
||||
@@ -528,7 +528,7 @@ TFMINI::collect()
|
||||
perf_begin(_sample_perf);
|
||||
|
||||
/* clear buffer if last read was too long ago */
|
||||
uint64_t read_elapsed = hrt_elapsed_time(&_last_read);
|
||||
int64_t read_elapsed = hrt_elapsed_time(&_last_read);
|
||||
|
||||
/* the buffer for read chars is buflen minus null termination */
|
||||
char readbuf[sizeof(_linebuf)];
|
||||
|
||||
@@ -34,7 +34,6 @@ px4_add_module(
|
||||
MODULE drivers__vmount
|
||||
MAIN vmount
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare # TODO: fix all sign-compare
|
||||
STACK_MAIN 1024
|
||||
SRCS
|
||||
input.cpp
|
||||
|
||||
@@ -72,11 +72,11 @@ using namespace vmount;
|
||||
static volatile bool thread_should_exit = false;
|
||||
static volatile bool thread_running = false;
|
||||
|
||||
static constexpr unsigned input_objs_len_max = 3;
|
||||
static constexpr int input_objs_len_max = 3;
|
||||
|
||||
struct ThreadData {
|
||||
InputBase *input_objs[input_objs_len_max] = {nullptr, nullptr, nullptr};
|
||||
unsigned input_objs_len = 0;
|
||||
int input_objs_len = 0;
|
||||
OutputBase *output_obj = nullptr;
|
||||
};
|
||||
static volatile ThreadData *g_thread_data = nullptr;
|
||||
|
||||
@@ -66,14 +66,14 @@ public:
|
||||
_state(),
|
||||
_fCut(this, "") // only one parameter, no need to name
|
||||
{
|
||||
for (int i = 0; i < M; i++) {
|
||||
for (size_t i = 0; i < M; i++) {
|
||||
_state(i) = 0.0f / 0.0f;
|
||||
}
|
||||
}
|
||||
virtual ~BlockLowPassVector() {}
|
||||
matrix::Vector<Type, M> update(const matrix::Matrix<Type, M, 1> &input)
|
||||
{
|
||||
for (int i = 0; i < M; i++) {
|
||||
for (size_t i = 0; i < M; i++) {
|
||||
if (!PX4_ISFINITE(getState()(i))) {
|
||||
setState(input);
|
||||
}
|
||||
|
||||
@@ -36,7 +36,6 @@ px4_add_module(
|
||||
STACK_MAIN 4096
|
||||
STACK_MAX 2450
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare # TODO: fix all sign-compare
|
||||
SRCS
|
||||
accelerometer_calibration.cpp
|
||||
airspeed_calibration.cpp
|
||||
|
||||
@@ -488,7 +488,7 @@ calibrate_return do_accel_calibration_measurements(orb_advert_t *mavlink_log_pub
|
||||
// and match it up with the one from the uORB subscription, because the
|
||||
// instance ordering of uORB and the order of the FDs may not be the same.
|
||||
|
||||
if(report.device_id == device_id[cur_accel]) {
|
||||
if (report.device_id == (uint32_t)device_id[cur_accel]) {
|
||||
// Device IDs match, correct ORB instance for this accel
|
||||
found_cur_accel = true;
|
||||
// store initial timestamp - used to infer which sensors are active
|
||||
|
||||
@@ -238,7 +238,7 @@ int sphere_fit_least_squares(const float x[], const float y[], const float z[],
|
||||
}
|
||||
|
||||
int ellipsoid_fit_least_squares(const float x[], const float y[], const float z[],
|
||||
unsigned int size, unsigned int max_iterations, float delta, float *offset_x, float *offset_y, float *offset_z,
|
||||
unsigned int size, int max_iterations, float delta, float *offset_x, float *offset_y, float *offset_z,
|
||||
float *sphere_radius, float *diag_x, float *diag_y, float *diag_z, float *offdiag_x, float *offdiag_y, float *offdiag_z)
|
||||
{
|
||||
float _fitness = 1.0e30f, _sphere_lambda = 1.0f, _ellipsoid_lambda = 1.0f;
|
||||
|
||||
@@ -58,7 +58,7 @@ int sphere_fit_least_squares(const float x[], const float y[], const float z[],
|
||||
unsigned int size, unsigned int max_iterations, float delta, float *sphere_x, float *sphere_y, float *sphere_z,
|
||||
float *sphere_radius);
|
||||
int ellipsoid_fit_least_squares(const float x[], const float y[], const float z[],
|
||||
unsigned int size, unsigned int max_iterations, float delta, float *offset_x, float *offset_y, float *offset_z,
|
||||
unsigned int size, int max_iterations, float delta, float *offset_x, float *offset_y, float *offset_z,
|
||||
float *sphere_radius, float *diag_x, float *diag_y, float *diag_z, float *offdiag_x, float *offdiag_y,
|
||||
float *offdiag_z);
|
||||
int run_lm_sphere_fit(const float x[], const float y[], const float z[], float &_fitness, float &_sphere_lambda,
|
||||
|
||||
@@ -1306,8 +1306,8 @@ Commander::run()
|
||||
|
||||
/* Start monitoring loop */
|
||||
unsigned counter = 0;
|
||||
unsigned stick_off_counter = 0;
|
||||
unsigned stick_on_counter = 0;
|
||||
int stick_off_counter = 0;
|
||||
int stick_on_counter = 0;
|
||||
|
||||
bool low_battery_voltage_actions_done = false;
|
||||
bool critical_battery_voltage_actions_done = false;
|
||||
@@ -3076,7 +3076,7 @@ Commander::set_main_state_rc(const vehicle_status_s &status_local, bool *changed
|
||||
/* we know something has changed - check if we are in mode slot operation */
|
||||
if (sp_man.mode_slot != manual_control_setpoint_s::MODE_SLOT_NONE) {
|
||||
|
||||
if (sp_man.mode_slot >= sizeof(_flight_mode_slots) / sizeof(_flight_mode_slots[0])) {
|
||||
if (sp_man.mode_slot >= (int)(sizeof(_flight_mode_slots) / sizeof(_flight_mode_slots[0]))) {
|
||||
warnx("m slot overflow");
|
||||
return TRANSITION_DENIED;
|
||||
}
|
||||
|
||||
@@ -316,7 +316,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
|
||||
// and match it up with the one from the uORB subscription, because the
|
||||
// instance ordering of uORB and the order of the FDs may not be the same.
|
||||
|
||||
if(report.device_id == worker_data.device_id[cur_gyro]) {
|
||||
if (report.device_id == (uint32_t)worker_data.device_id[cur_gyro]) {
|
||||
// Device IDs match, correct ORB instance for this gyro
|
||||
found_cur_gyro = true;
|
||||
} else {
|
||||
|
||||
@@ -609,7 +609,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub)
|
||||
// and match it up with the one from the uORB subscription, because the
|
||||
// instance ordering of uORB and the order of the FDs may not be the same.
|
||||
|
||||
if(report.device_id == device_ids[cur_mag]) {
|
||||
if (report.device_id == (uint32_t)device_ids[cur_mag]) {
|
||||
// Device IDs match, correct ORB instance for this mag
|
||||
found_cur_mag = true;
|
||||
} else {
|
||||
|
||||
@@ -35,7 +35,6 @@ px4_add_module(
|
||||
MAIN dataman
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare # TODO: fix all sign-compare
|
||||
SRCS
|
||||
dataman.cpp
|
||||
)
|
||||
|
||||
@@ -808,7 +808,7 @@ static int _ram_restart(dm_reset_reason reason)
|
||||
static int
|
||||
_file_restart(dm_reset_reason reason)
|
||||
{
|
||||
unsigned offset = 0;
|
||||
int offset = 0;
|
||||
int result = 0;
|
||||
/* We need to scan the entire file and invalidate and data that should not persist after the last reset */
|
||||
|
||||
|
||||
@@ -34,7 +34,6 @@ px4_add_module(
|
||||
MODULE modules__ekf2
|
||||
MAIN ekf2
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare # TODO: fix all sign-compare
|
||||
STACK_MAIN 2500
|
||||
STACK_MAX 4000
|
||||
SRCS
|
||||
|
||||
@@ -130,8 +130,7 @@ private:
|
||||
float _mag_data_sum[3] = {}; ///< summed magnetometer readings (Gauss)
|
||||
uint64_t _mag_time_sum_ms = 0; ///< summed magnetoemter time stamps (mSec)
|
||||
uint8_t _mag_sample_count = 0; ///< number of magnetometer measurements summed during downsampling
|
||||
uint32_t _mag_time_ms_last_used =
|
||||
0; ///< time stamp of the last averaged magnetometer measurement sent to the EKF (mSec)
|
||||
int32_t _mag_time_ms_last_used = 0; ///< time stamp of the last averaged magnetometer measurement sent to the EKF (mSec)
|
||||
|
||||
// Used to down sample barometer data
|
||||
float _balt_data_sum = 0.0f; ///< summed pressure altitude readings (m)
|
||||
@@ -724,7 +723,7 @@ void Ekf2::run()
|
||||
// Do not reset parmameters when armed to prevent potential time slips casued by parameter set
|
||||
// and notification events
|
||||
// Check if there has been a persistant change in magnetometer ID
|
||||
if (sensor_selection.mag_device_id != 0 && sensor_selection.mag_device_id != _mag_bias_id.get()) {
|
||||
if (sensor_selection.mag_device_id != 0 && sensor_selection.mag_device_id != (uint32_t)_mag_bias_id.get()) {
|
||||
if (_invalid_mag_id_count < 200) {
|
||||
_invalid_mag_id_count++;
|
||||
}
|
||||
@@ -759,9 +758,9 @@ void Ekf2::run()
|
||||
_mag_data_sum[0] += magnetometer.magnetometer_ga[0];
|
||||
_mag_data_sum[1] += magnetometer.magnetometer_ga[1];
|
||||
_mag_data_sum[2] += magnetometer.magnetometer_ga[2];
|
||||
uint32_t mag_time_ms = _mag_time_sum_ms / _mag_sample_count;
|
||||
int32_t mag_time_ms = _mag_time_sum_ms / _mag_sample_count;
|
||||
|
||||
if (mag_time_ms - _mag_time_ms_last_used > _params->sensor_interval_min_ms) {
|
||||
if ((mag_time_ms - _mag_time_ms_last_used) > _params->sensor_interval_min_ms) {
|
||||
const float mag_sample_count_inv = 1.0f / _mag_sample_count;
|
||||
// calculate mean of measurements and correct for learned bias offsets
|
||||
float mag_data_avg_ga[3] = {_mag_data_sum[0] *mag_sample_count_inv - _mag_bias_x.get(),
|
||||
@@ -1337,7 +1336,7 @@ void Ekf2::run()
|
||||
// Check and save the last valid calibration when we are disarmed
|
||||
if ((vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_STANDBY)
|
||||
&& (status.filter_fault_flags == 0)
|
||||
&& (sensor_selection.mag_device_id == _mag_bias_id.get())) {
|
||||
&& (sensor_selection.mag_device_id == (uint32_t)_mag_bias_id.get())) {
|
||||
|
||||
update_mag_bias(_mag_bias_x, 0);
|
||||
update_mag_bias(_mag_bias_y, 1);
|
||||
|
||||
@@ -36,7 +36,6 @@ px4_add_module(
|
||||
MAIN send_event
|
||||
STACK_MAIN 2200
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare # TODO: fix all sign-compare
|
||||
SRCS
|
||||
send_event.cpp
|
||||
temperature_calibration/accel.cpp
|
||||
|
||||
@@ -112,7 +112,7 @@ Author: Siddharth Bharat Purohit
|
||||
#define PF_DEBUG(fmt, ...)
|
||||
#endif
|
||||
|
||||
template<size_t _forder>
|
||||
template<int _forder>
|
||||
class polyfitter
|
||||
{
|
||||
public:
|
||||
@@ -131,7 +131,7 @@ public:
|
||||
|
||||
IVTV = _VTV.I();
|
||||
|
||||
for (unsigned i = 0; i < _forder; i++) {
|
||||
for (int i = 0; i < _forder; i++) {
|
||||
for (int j = 0; j < _forder; j++) {
|
||||
PF_DEBUG("%.10f ", (double)IVTV(i, j));
|
||||
}
|
||||
@@ -139,7 +139,7 @@ public:
|
||||
PF_DEBUG("\n");
|
||||
}
|
||||
|
||||
for (unsigned i = 0; i < _forder; i++) {
|
||||
for (int i = 0; i < _forder; i++) {
|
||||
res[i] = 0.0;
|
||||
|
||||
for (int j = 0; j < _forder; j++) {
|
||||
@@ -161,7 +161,7 @@ private:
|
||||
double temp = 1.0;
|
||||
PF_DEBUG("O %.6f\n", (double)x);
|
||||
|
||||
for (int8_t i = _forder - 1; i >= 0; i--) {
|
||||
for (int i = _forder - 1; i >= 0; i--) {
|
||||
_VTY(i) += y * temp;
|
||||
temp *= x;
|
||||
PF_DEBUG("%.6f ", (double)_VTY(i));
|
||||
@@ -175,7 +175,7 @@ private:
|
||||
double temp = 1.0;
|
||||
int8_t z;
|
||||
|
||||
for (unsigned i = 0; i < _forder; i++) {
|
||||
for (int i = 0; i < _forder; i++) {
|
||||
for (int j = 0; j < _forder; j++) {
|
||||
PF_DEBUG("%.10f ", (double)_VTV(i, j));
|
||||
}
|
||||
@@ -183,7 +183,7 @@ private:
|
||||
PF_DEBUG("\n");
|
||||
}
|
||||
|
||||
for (int8_t i = 2 * _forder - 2; i >= 0; i--) {
|
||||
for (int i = 2 * _forder - 2; i >= 0; i--) {
|
||||
if (i < _forder) {
|
||||
z = 0.0f;
|
||||
|
||||
@@ -192,8 +192,8 @@ private:
|
||||
}
|
||||
|
||||
for (int j = i - z; j >= z; j--) {
|
||||
unsigned row = j;
|
||||
unsigned col = i - j;
|
||||
int row = j;
|
||||
int col = i - j;
|
||||
_VTV(row, col) += (double)temp;
|
||||
}
|
||||
|
||||
|
||||
@@ -217,7 +217,7 @@ void TemperatureCalibration::task_main()
|
||||
if (!_gyro) {
|
||||
sensor_gyro_s gyro_data;
|
||||
|
||||
for (int i = 0; i < num_gyro; ++i) {
|
||||
for (unsigned i = 0; i < num_gyro; ++i) {
|
||||
orb_copy(ORB_ID(sensor_gyro), gyro_sub[i], &gyro_data);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -190,7 +190,7 @@ void BlockLocalPositionEstimator::update()
|
||||
|
||||
if (!armedState && (_sub_lidar == nullptr || _sub_sonar == nullptr)) {
|
||||
// detect distance sensors
|
||||
for (int i = 0; i < N_DIST_SUBS; i++) {
|
||||
for (size_t i = 0; i < N_DIST_SUBS; i++) {
|
||||
uORB::Subscription<distance_sensor_s> *s = _dist_subs[i];
|
||||
|
||||
if (s == _sub_lidar || s == _sub_sonar) { continue; }
|
||||
|
||||
@@ -34,7 +34,6 @@ px4_add_module(
|
||||
MODULE modules__local_position_estimator
|
||||
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
|
||||
|
||||
@@ -37,7 +37,6 @@ px4_add_module(
|
||||
PRIORITY "SCHED_PRIORITY_MAX-30"
|
||||
STACK_MAIN 2200
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare # TODO: fix all sign-compare
|
||||
SRCS
|
||||
logger.cpp
|
||||
log_writer.cpp
|
||||
|
||||
@@ -888,7 +888,8 @@ void Logger::run()
|
||||
}
|
||||
|
||||
//all topics added. Get required message buffer size
|
||||
int max_msg_size = 0, ret;
|
||||
int max_msg_size = 0;
|
||||
int ret = 0;
|
||||
|
||||
for (const auto &subscription : _subscriptions) {
|
||||
//use o_size, because that's what orb_copy will use
|
||||
@@ -899,7 +900,7 @@ void Logger::run()
|
||||
|
||||
max_msg_size += sizeof(ulog_message_data_header_s);
|
||||
|
||||
if (sizeof(ulog_message_logging_s) > max_msg_size) {
|
||||
if (sizeof(ulog_message_logging_s) > (size_t)max_msg_size) {
|
||||
max_msg_size = sizeof(ulog_message_logging_s);
|
||||
}
|
||||
|
||||
@@ -1161,7 +1162,7 @@ void Logger::run()
|
||||
|
||||
/* subscription update */
|
||||
if (next_subscribe_topic_index != -1) {
|
||||
if (++next_subscribe_topic_index >= _subscriptions.size()) {
|
||||
if (++next_subscribe_topic_index >= (int)_subscriptions.size()) {
|
||||
next_subscribe_topic_index = -1;
|
||||
next_subscribe_check = loop_time + TRY_SUBSCRIBE_INTERVAL;
|
||||
}
|
||||
@@ -1199,7 +1200,7 @@ void Logger::run()
|
||||
try_to_subscribe_topic(_subscriptions[next_subscribe_topic_index], instance);
|
||||
}
|
||||
}
|
||||
if (++next_subscribe_topic_index >= _subscriptions.size()) {
|
||||
if (++next_subscribe_topic_index >= (int)_subscriptions.size()) {
|
||||
next_subscribe_topic_index = -1;
|
||||
next_subscribe_check = loop_time + TRY_SUBSCRIBE_INTERVAL;
|
||||
}
|
||||
@@ -1310,7 +1311,7 @@ int Logger::create_log_dir(tm *tt)
|
||||
if (tt) {
|
||||
int n = snprintf(_log_dir, sizeof(_log_dir), "%s/", LOG_ROOT);
|
||||
|
||||
if (n >= sizeof(_log_dir)) {
|
||||
if (n >= (int)sizeof(_log_dir)) {
|
||||
PX4_ERR("log path too long");
|
||||
return -1;
|
||||
}
|
||||
@@ -1331,7 +1332,7 @@ int Logger::create_log_dir(tm *tt)
|
||||
/* format log dir: e.g. /fs/microsd/sess001 */
|
||||
int n = snprintf(_log_dir, sizeof(_log_dir), "%s/sess%03u", LOG_ROOT, dir_number);
|
||||
|
||||
if (n >= sizeof(_log_dir)) {
|
||||
if (n >= (int)sizeof(_log_dir)) {
|
||||
PX4_ERR("log path too long (%i)", n);
|
||||
return -1;
|
||||
}
|
||||
@@ -2149,7 +2150,7 @@ int Logger::check_free_space()
|
||||
day_min);
|
||||
}
|
||||
|
||||
if (n >= sizeof(directory_to_delete)) {
|
||||
if (n >= (int)sizeof(directory_to_delete)) {
|
||||
PX4_ERR("log path too long (%i)", n);
|
||||
break;
|
||||
}
|
||||
|
||||
@@ -39,7 +39,6 @@ px4_add_module(
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 1500
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare # TODO: fix all sign-compare
|
||||
INCLUDES
|
||||
${PX4_SOURCE_DIR}/mavlink/include/mavlink
|
||||
SRCS
|
||||
|
||||
@@ -477,7 +477,7 @@ LogListHelper::_init()
|
||||
time_t tt = 0;
|
||||
char log_path[128];
|
||||
int ret = snprintf(log_path, sizeof(log_path), "%s/%s", kLogRoot, result->d_name);
|
||||
bool path_is_ok = (ret > 0) && (ret < sizeof(log_path));
|
||||
bool path_is_ok = (ret > 0) && (ret < (int)sizeof(log_path));
|
||||
|
||||
if (path_is_ok) {
|
||||
if (_get_session_date(log_path, result->d_name, tt)) {
|
||||
@@ -539,7 +539,7 @@ LogListHelper::_scan_logs(FILE *f, const char *dir, time_t &date)
|
||||
uint32_t size = 0;
|
||||
char log_file_path[128];
|
||||
int ret = snprintf(log_file_path, sizeof(log_file_path), "%s/%s", dir, result->d_name);
|
||||
bool path_is_ok = (ret > 0) && (ret < sizeof(log_file_path));
|
||||
bool path_is_ok = (ret > 0) && (ret < (int)sizeof(log_file_path));
|
||||
|
||||
if (path_is_ok) {
|
||||
if (_get_log_time_size(log_file_path, result->d_name, ldate, size)) {
|
||||
@@ -609,7 +609,7 @@ LogListHelper::delete_all(const char *dir)
|
||||
if (result->d_type == PX4LOG_DIRECTORY && result->d_name[0] != '.') {
|
||||
char log_path[128];
|
||||
int ret = snprintf(log_path, sizeof(log_path), "%s/%s", dir, result->d_name);
|
||||
bool path_is_ok = (ret > 0) && (ret < sizeof(log_path));
|
||||
bool path_is_ok = (ret > 0) && (ret < (int)sizeof(log_path));
|
||||
|
||||
if (path_is_ok) {
|
||||
LogListHelper::delete_all(log_path);
|
||||
@@ -623,7 +623,7 @@ LogListHelper::delete_all(const char *dir)
|
||||
if (result->d_type == PX4LOG_REGULAR_FILE) {
|
||||
char log_path[128];
|
||||
int ret = snprintf(log_path, sizeof(log_path), "%s/%s", dir, result->d_name);
|
||||
bool path_is_ok = (ret > 0) && (ret < sizeof(log_path));
|
||||
bool path_is_ok = (ret > 0) && (ret < (int)sizeof(log_path));
|
||||
|
||||
if (path_is_ok) {
|
||||
if (unlink(log_path)) {
|
||||
|
||||
@@ -115,7 +115,7 @@ extern mavlink_system_t mavlink_system;
|
||||
|
||||
void mavlink_send_uart_bytes(mavlink_channel_t chan, const uint8_t *ch, int length)
|
||||
{
|
||||
Mavlink *m = Mavlink::get_instance((unsigned)chan);
|
||||
Mavlink *m = Mavlink::get_instance(chan);
|
||||
|
||||
if (m != nullptr) {
|
||||
m->send_bytes(ch, length);
|
||||
@@ -131,7 +131,7 @@ void mavlink_send_uart_bytes(mavlink_channel_t chan, const uint8_t *ch, int leng
|
||||
|
||||
void mavlink_start_uart_send(mavlink_channel_t chan, int length)
|
||||
{
|
||||
Mavlink *m = Mavlink::get_instance((unsigned)chan);
|
||||
Mavlink *m = Mavlink::get_instance(chan);
|
||||
|
||||
if (m != nullptr) {
|
||||
(void)m->begin_send();
|
||||
@@ -143,7 +143,7 @@ void mavlink_start_uart_send(mavlink_channel_t chan, int length)
|
||||
|
||||
void mavlink_end_uart_send(mavlink_channel_t chan, int length)
|
||||
{
|
||||
Mavlink *m = Mavlink::get_instance((unsigned)chan);
|
||||
Mavlink *m = Mavlink::get_instance(chan);
|
||||
|
||||
if (m != nullptr) {
|
||||
(void)m->send_packet();
|
||||
@@ -158,7 +158,7 @@ void mavlink_end_uart_send(mavlink_channel_t chan, int length)
|
||||
*/
|
||||
mavlink_status_t *mavlink_get_channel_status(uint8_t channel)
|
||||
{
|
||||
Mavlink *m = Mavlink::get_instance((unsigned)channel);
|
||||
Mavlink *m = Mavlink::get_instance(channel);
|
||||
|
||||
if (m != nullptr) {
|
||||
return m->get_status();
|
||||
@@ -173,7 +173,7 @@ mavlink_status_t *mavlink_get_channel_status(uint8_t channel)
|
||||
*/
|
||||
mavlink_message_t *mavlink_get_channel_buffer(uint8_t channel)
|
||||
{
|
||||
Mavlink *m = Mavlink::get_instance((unsigned)channel);
|
||||
Mavlink *m = Mavlink::get_instance(channel);
|
||||
|
||||
if (m != nullptr) {
|
||||
return m->get_buffer();
|
||||
@@ -386,7 +386,7 @@ Mavlink::instance_count()
|
||||
}
|
||||
|
||||
Mavlink *
|
||||
Mavlink::get_instance(unsigned instance)
|
||||
Mavlink::get_instance(int instance)
|
||||
{
|
||||
Mavlink *inst;
|
||||
LL_FOREACH(::_mavlink_instances, inst) {
|
||||
@@ -524,8 +524,8 @@ Mavlink::forward_message(const mavlink_message_t *msg, Mavlink *self)
|
||||
const mavlink_msg_entry_t *meta = mavlink_get_msg_entry(msg->msgid);
|
||||
|
||||
// Extract target system and target component if set
|
||||
unsigned target_system_id = (meta->target_system_ofs != 0) ? ((uint8_t *)msg)[meta->target_system_ofs] : 0;
|
||||
unsigned target_component_id = (meta->target_component_ofs != 0) ? ((uint8_t *)msg)[meta->target_component_ofs] : 233;
|
||||
int target_system_id = (meta->target_system_ofs != 0) ? ((uint8_t *)msg)[meta->target_system_ofs] : 0;
|
||||
int target_component_id = (meta->target_component_ofs != 0) ? ((uint8_t *)msg)[meta->target_component_ofs] : 233;
|
||||
|
||||
// Broadcast or addressing this system and not trying to talk
|
||||
// to the autopilot component -> pass on to other components
|
||||
@@ -1088,7 +1088,7 @@ Mavlink::find_broadcast_address()
|
||||
return;
|
||||
}
|
||||
|
||||
size_t offset = 0;
|
||||
int offset = 0;
|
||||
// Later used to point to next network interface in buffer.
|
||||
struct ifreq *cur_ifreq = (struct ifreq *) & (((uint8_t *)ifconf.ifc_req)[offset]);
|
||||
|
||||
|
||||
@@ -120,7 +120,7 @@ public:
|
||||
|
||||
static Mavlink *new_instance();
|
||||
|
||||
static Mavlink *get_instance(unsigned instance);
|
||||
static Mavlink *get_instance(int instance);
|
||||
|
||||
static Mavlink *get_instance_for_device(const char *device_name);
|
||||
|
||||
@@ -510,9 +510,9 @@ private:
|
||||
orb_advert_t _mavlink_log_pub;
|
||||
bool _task_running;
|
||||
static bool _boot_complete;
|
||||
static constexpr unsigned MAVLINK_MAX_INSTANCES = 4;
|
||||
static constexpr unsigned MAVLINK_MIN_INTERVAL = 1500;
|
||||
static constexpr unsigned MAVLINK_MAX_INTERVAL = 10000;
|
||||
static constexpr int MAVLINK_MAX_INSTANCES = 4;
|
||||
static constexpr int MAVLINK_MIN_INTERVAL = 1500;
|
||||
static constexpr int MAVLINK_MAX_INTERVAL = 10000;
|
||||
static constexpr float MAVLINK_MIN_MULTIPLIER = 0.0005f;
|
||||
mavlink_message_t _mavlink_buffer;
|
||||
mavlink_status_t _mavlink_status;
|
||||
|
||||
@@ -38,7 +38,6 @@ px4_add_module(
|
||||
MAIN mavlink_tests
|
||||
STACK_MAIN 5000
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare # TODO: fix all sign-compare
|
||||
-DMAVLINK_FTP_UNIT_TEST
|
||||
#-DMAVLINK_FTP_DEBUG
|
||||
-DMavlinkStream=MavlinkStreamTest
|
||||
|
||||
@@ -34,7 +34,6 @@ px4_add_module(
|
||||
MODULE modules__replay
|
||||
MAIN replay
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare # TODO: fix all sign-compare
|
||||
STACK_MAIN 1000
|
||||
STACK_MAX 4000
|
||||
SRCS
|
||||
|
||||
@@ -219,7 +219,7 @@ private:
|
||||
/** keep track of file position to avoid adding a subscription multiple times. */
|
||||
std::streampos _subscription_file_pos = 0;
|
||||
|
||||
uint64_t _read_until_file_position = 1ULL << 60; ///< read limit if log contains appended data
|
||||
int64_t _read_until_file_position = 1ULL << 60; ///< read limit if log contains appended data
|
||||
|
||||
bool readFileHeader(std::ifstream &file);
|
||||
|
||||
|
||||
@@ -37,7 +37,6 @@ px4_add_module(
|
||||
PRIORITY "SCHED_PRIORITY_MAX-5"
|
||||
STACK_MAIN 1300
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare # TODO: fix all sign-compare
|
||||
SRCS
|
||||
voted_sensors_update.cpp
|
||||
rc_update.cpp
|
||||
|
||||
@@ -368,7 +368,7 @@ int TemperatureCompensation::set_sensor_id(uint32_t device_id, int topic_instanc
|
||||
const T *sensor_cal_data, uint8_t sensor_count_max)
|
||||
{
|
||||
for (int i = 0; i < sensor_count_max; ++i) {
|
||||
if (device_id == sensor_cal_data[i].ID) {
|
||||
if (device_id == (uint32_t)sensor_cal_data[i].ID) {
|
||||
sensor_data.device_mapping[topic_instance] = i;
|
||||
return i;
|
||||
}
|
||||
|
||||
@@ -111,19 +111,19 @@ void VotedSensorsUpdate::initialize_sensors()
|
||||
|
||||
void VotedSensorsUpdate::deinit()
|
||||
{
|
||||
for (unsigned i = 0; i < _gyro.subscription_count; i++) {
|
||||
for (int i = 0; i < _gyro.subscription_count; i++) {
|
||||
orb_unsubscribe(_gyro.subscription[i]);
|
||||
}
|
||||
|
||||
for (unsigned i = 0; i < _accel.subscription_count; i++) {
|
||||
for (int i = 0; i < _accel.subscription_count; i++) {
|
||||
orb_unsubscribe(_accel.subscription[i]);
|
||||
}
|
||||
|
||||
for (unsigned i = 0; i < _mag.subscription_count; i++) {
|
||||
for (int i = 0; i < _mag.subscription_count; i++) {
|
||||
orb_unsubscribe(_mag.subscription[i]);
|
||||
}
|
||||
|
||||
for (unsigned i = 0; i < _baro.subscription_count; i++) {
|
||||
for (int i = 0; i < _baro.subscription_count; i++) {
|
||||
orb_unsubscribe(_baro.subscription[i]);
|
||||
}
|
||||
}
|
||||
@@ -151,7 +151,7 @@ void VotedSensorsUpdate::parameters_update()
|
||||
_temperature_compensation.parameters_update();
|
||||
|
||||
/* gyro */
|
||||
for (unsigned topic_instance = 0; topic_instance < GYRO_COUNT_MAX; ++topic_instance) {
|
||||
for (int topic_instance = 0; topic_instance < GYRO_COUNT_MAX; ++topic_instance) {
|
||||
|
||||
if (topic_instance < _gyro.subscription_count) {
|
||||
// valid subscription, so get the driver id by getting the published sensor data
|
||||
@@ -175,7 +175,7 @@ void VotedSensorsUpdate::parameters_update()
|
||||
|
||||
|
||||
/* accel */
|
||||
for (unsigned topic_instance = 0; topic_instance < ACCEL_COUNT_MAX; ++topic_instance) {
|
||||
for (int topic_instance = 0; topic_instance < ACCEL_COUNT_MAX; ++topic_instance) {
|
||||
|
||||
if (topic_instance < _accel.subscription_count) {
|
||||
// valid subscription, so get the driver id by getting the published sensor data
|
||||
@@ -198,7 +198,7 @@ void VotedSensorsUpdate::parameters_update()
|
||||
}
|
||||
|
||||
/* baro */
|
||||
for (unsigned topic_instance = 0; topic_instance < BARO_COUNT_MAX; ++topic_instance) {
|
||||
for (int topic_instance = 0; topic_instance < BARO_COUNT_MAX; ++topic_instance) {
|
||||
|
||||
if (topic_instance < _baro.subscription_count) {
|
||||
// valid subscription, so get the driver id by getting the published sensor data
|
||||
@@ -250,7 +250,7 @@ void VotedSensorsUpdate::parameters_update()
|
||||
failed = false;
|
||||
|
||||
(void)sprintf(str, "CAL_GYRO%u_ID", i);
|
||||
int32_t device_id;
|
||||
int32_t device_id = 0;
|
||||
failed = failed || (OK != param_get(param_find(str), &device_id));
|
||||
|
||||
(void)sprintf(str, "CAL_GYRO%u_EN", i);
|
||||
@@ -268,7 +268,7 @@ void VotedSensorsUpdate::parameters_update()
|
||||
}
|
||||
|
||||
/* if the calibration is for this device, apply it */
|
||||
if (device_id == driver_device_id) {
|
||||
if ((uint32_t)device_id == driver_device_id) {
|
||||
struct gyro_calibration_s gscale = {};
|
||||
(void)sprintf(str, "CAL_GYRO%u_XOFF", i);
|
||||
failed = failed || (OK != param_get(param_find(str), &gscale.x_offset));
|
||||
@@ -338,7 +338,7 @@ void VotedSensorsUpdate::parameters_update()
|
||||
failed = false;
|
||||
|
||||
(void)sprintf(str, "CAL_ACC%u_ID", i);
|
||||
int32_t device_id;
|
||||
int32_t device_id = 0;
|
||||
failed = failed || (OK != param_get(param_find(str), &device_id));
|
||||
|
||||
(void)sprintf(str, "CAL_ACC%u_EN", i);
|
||||
@@ -356,7 +356,7 @@ void VotedSensorsUpdate::parameters_update()
|
||||
}
|
||||
|
||||
/* if the calibration is for this device, apply it */
|
||||
if (device_id == driver_device_id) {
|
||||
if ((uint32_t)device_id == driver_device_id) {
|
||||
struct accel_calibration_s ascale = {};
|
||||
(void)sprintf(str, "CAL_ACC%u_XOFF", i);
|
||||
failed = failed || (OK != param_get(param_find(str), &ascale.x_offset));
|
||||
@@ -409,8 +409,8 @@ void VotedSensorsUpdate::parameters_update()
|
||||
* Because we store the device id in _mag_device_id, we need to get the id via uorb topic since
|
||||
* the DevHandle method does not work on POSIX.
|
||||
*/
|
||||
for (unsigned topic_instance = 0; topic_instance < MAG_COUNT_MAX && topic_instance < _mag.subscription_count;
|
||||
++topic_instance) {
|
||||
for (int topic_instance = 0; topic_instance < MAG_COUNT_MAX
|
||||
&& topic_instance < _mag.subscription_count; ++topic_instance) {
|
||||
|
||||
struct mag_report report;
|
||||
|
||||
@@ -454,7 +454,7 @@ void VotedSensorsUpdate::parameters_update()
|
||||
failed = false;
|
||||
|
||||
(void)sprintf(str, "CAL_MAG%u_ID", i);
|
||||
int32_t device_id;
|
||||
int32_t device_id = 0;
|
||||
failed = failed || (OK != param_get(param_find(str), &device_id));
|
||||
|
||||
(void)sprintf(str, "CAL_MAG%u_EN", i);
|
||||
@@ -468,7 +468,7 @@ void VotedSensorsUpdate::parameters_update()
|
||||
}
|
||||
|
||||
/* if the calibration is for this device, apply it */
|
||||
if (device_id == _mag_device_id[topic_instance]) {
|
||||
if ((uint32_t)device_id == _mag_device_id[topic_instance]) {
|
||||
struct mag_calibration_s mscale = {};
|
||||
(void)sprintf(str, "CAL_MAG%u_XOFF", i);
|
||||
failed = failed || (OK != param_get(param_find(str), &mscale.x_offset));
|
||||
@@ -540,7 +540,7 @@ void VotedSensorsUpdate::accel_poll(struct sensor_combined_s &raw)
|
||||
float *offsets[] = {_corrections.accel_offset_0, _corrections.accel_offset_1, _corrections.accel_offset_2 };
|
||||
float *scales[] = {_corrections.accel_scale_0, _corrections.accel_scale_1, _corrections.accel_scale_2 };
|
||||
|
||||
for (unsigned uorb_index = 0; uorb_index < _accel.subscription_count; uorb_index++) {
|
||||
for (int uorb_index = 0; uorb_index < _accel.subscription_count; uorb_index++) {
|
||||
bool accel_updated;
|
||||
orb_check(_accel.subscription[uorb_index], &accel_updated);
|
||||
|
||||
@@ -645,7 +645,7 @@ void VotedSensorsUpdate::gyro_poll(struct sensor_combined_s &raw)
|
||||
float *offsets[] = {_corrections.gyro_offset_0, _corrections.gyro_offset_1, _corrections.gyro_offset_2 };
|
||||
float *scales[] = {_corrections.gyro_scale_0, _corrections.gyro_scale_1, _corrections.gyro_scale_2 };
|
||||
|
||||
for (unsigned uorb_index = 0; uorb_index < _gyro.subscription_count; uorb_index++) {
|
||||
for (int uorb_index = 0; uorb_index < _gyro.subscription_count; uorb_index++) {
|
||||
bool gyro_updated;
|
||||
orb_check(_gyro.subscription[uorb_index], &gyro_updated);
|
||||
|
||||
@@ -748,7 +748,7 @@ void VotedSensorsUpdate::gyro_poll(struct sensor_combined_s &raw)
|
||||
|
||||
void VotedSensorsUpdate::mag_poll(vehicle_magnetometer_s &magnetometer)
|
||||
{
|
||||
for (unsigned uorb_index = 0; uorb_index < _mag.subscription_count; uorb_index++) {
|
||||
for (int uorb_index = 0; uorb_index < _mag.subscription_count; uorb_index++) {
|
||||
bool mag_updated;
|
||||
orb_check(_mag.subscription[uorb_index], &mag_updated);
|
||||
|
||||
@@ -800,7 +800,7 @@ void VotedSensorsUpdate::baro_poll(vehicle_air_data_s &airdata)
|
||||
float *offsets[] = {&_corrections.baro_offset_0, &_corrections.baro_offset_1, &_corrections.baro_offset_2 };
|
||||
float *scales[] = {&_corrections.baro_scale_0, &_corrections.baro_scale_1, &_corrections.baro_scale_2 };
|
||||
|
||||
for (unsigned uorb_index = 0; uorb_index < _baro.subscription_count; uorb_index++) {
|
||||
for (int uorb_index = 0; uorb_index < _baro.subscription_count; uorb_index++) {
|
||||
bool baro_updated;
|
||||
orb_check(_baro.subscription[uorb_index], &baro_updated);
|
||||
|
||||
@@ -1115,7 +1115,7 @@ VotedSensorsUpdate::calc_accel_inconsistency(sensor_preflight_s &preflt)
|
||||
unsigned check_index = 0; // the number of sensors the primary has been checked against
|
||||
|
||||
// Check each sensor against the primary
|
||||
for (unsigned sensor_index = 0; sensor_index < _accel.subscription_count; sensor_index++) {
|
||||
for (int sensor_index = 0; sensor_index < _accel.subscription_count; sensor_index++) {
|
||||
|
||||
// check that the sensor we are checking against is not the same as the primary
|
||||
if ((_accel.priority[sensor_index] > 0) && (sensor_index != _accel.last_best_vote)) {
|
||||
@@ -1164,7 +1164,7 @@ void VotedSensorsUpdate::calc_gyro_inconsistency(sensor_preflight_s &preflt)
|
||||
unsigned check_index = 0; // the number of sensors the primary has been checked against
|
||||
|
||||
// Check each sensor against the primary
|
||||
for (unsigned sensor_index = 0; sensor_index < _gyro.subscription_count; sensor_index++) {
|
||||
for (int sensor_index = 0; sensor_index < _gyro.subscription_count; sensor_index++) {
|
||||
|
||||
// check that the sensor we are checking against is not the same as the primary
|
||||
if ((_gyro.priority[sensor_index] > 0) && (sensor_index != _gyro.last_best_vote)) {
|
||||
@@ -1213,7 +1213,7 @@ void VotedSensorsUpdate::calc_mag_inconsistency(sensor_preflight_s &preflt)
|
||||
unsigned check_index = 0; // the number of sensors the primary has been checked against
|
||||
|
||||
// Check each sensor against the primary
|
||||
for (unsigned sensor_index = 0; sensor_index < _mag.subscription_count; sensor_index++) {
|
||||
for (int sensor_index = 0; sensor_index < _mag.subscription_count; sensor_index++) {
|
||||
|
||||
// check that the sensor we are checking against is not the same as the primary
|
||||
if ((_mag.priority[sensor_index] > 0) && (sensor_index != _mag.last_best_vote)) {
|
||||
|
||||
@@ -211,7 +211,7 @@ AirspeedSim::ioctl(device::file_t *filp, int cmd, unsigned long arg)
|
||||
bool want_start = (_measure_ticks == 0);
|
||||
|
||||
/* convert hz to tick interval via microseconds */
|
||||
unsigned long ticks = USEC2TICK(1000000 / arg);
|
||||
int ticks = USEC2TICK(1000000 / arg);
|
||||
|
||||
/* check against maximum rate */
|
||||
if (ticks < USEC2TICK(_conversion_interval)) {
|
||||
|
||||
@@ -117,7 +117,7 @@ protected:
|
||||
|
||||
struct work_s _work;
|
||||
bool _sensor_ok;
|
||||
unsigned _measure_ticks;
|
||||
int _measure_ticks;
|
||||
bool _collect_phase;
|
||||
float _diff_pres_offset;
|
||||
|
||||
@@ -125,7 +125,7 @@ protected:
|
||||
|
||||
int _class_instance;
|
||||
|
||||
unsigned _conversion_interval;
|
||||
int _conversion_interval;
|
||||
|
||||
perf_counter_t _sample_perf;
|
||||
perf_counter_t _comms_errors;
|
||||
|
||||
@@ -53,7 +53,6 @@ endif()
|
||||
# TODO: find a better way to do this
|
||||
if (NOT "${CONFIG}" MATCHES "px4io")
|
||||
px4_add_library(systemlib ${SRCS})
|
||||
target_compile_options(systemlib PRIVATE -Wno-sign-compare)
|
||||
else()
|
||||
add_library(systemlib ${PX4_SOURCE_DIR}/src/platforms/empty.c)
|
||||
add_dependencies(systemlib prebuild_targets)
|
||||
|
||||
@@ -45,7 +45,6 @@ px4_add_module(
|
||||
MAIN uorb_tests
|
||||
STACK_MAIN 2048
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare # TODO: fix all sign-compare
|
||||
SRCS ${SRCS}
|
||||
DEPENDS
|
||||
)
|
||||
|
||||
@@ -610,7 +610,7 @@ int uORBTest::UnitTest::test_queue()
|
||||
}
|
||||
|
||||
|
||||
const unsigned int queue_size = 11;
|
||||
const int queue_size = 11;
|
||||
t.val = 0;
|
||||
ptopic = orb_advertise_queue(ORB_ID(orb_test_medium_queue), &t, queue_size);
|
||||
|
||||
@@ -658,12 +658,12 @@ int uORBTest::UnitTest::test_queue()
|
||||
|
||||
test_note(" Testing to write some elements...");
|
||||
|
||||
for (unsigned int i = 0; i < queue_size - 2; ++i) {
|
||||
for (int i = 0; i < queue_size - 2; ++i) {
|
||||
t.val = i;
|
||||
orb_publish(ORB_ID(orb_test_medium_queue), ptopic, &t);
|
||||
}
|
||||
|
||||
for (unsigned int i = 0; i < queue_size - 2; ++i) {
|
||||
for (int i = 0; i < queue_size - 2; ++i) {
|
||||
CHECK_UPDATED(i);
|
||||
CHECK_COPY(u.val, i);
|
||||
}
|
||||
@@ -673,12 +673,12 @@ int uORBTest::UnitTest::test_queue()
|
||||
test_note(" Testing overflow...");
|
||||
int overflow_by = 3;
|
||||
|
||||
for (unsigned int i = 0; i < queue_size + overflow_by; ++i) {
|
||||
for (int i = 0; i < queue_size + overflow_by; ++i) {
|
||||
t.val = i;
|
||||
orb_publish(ORB_ID(orb_test_medium_queue), ptopic, &t);
|
||||
}
|
||||
|
||||
for (unsigned int i = 0; i < queue_size; ++i) {
|
||||
for (int i = 0; i < queue_size; ++i) {
|
||||
CHECK_UPDATED(i);
|
||||
CHECK_COPY(u.val, i + overflow_by);
|
||||
}
|
||||
@@ -687,7 +687,7 @@ int uORBTest::UnitTest::test_queue()
|
||||
|
||||
test_note(" Testing underflow...");
|
||||
|
||||
for (unsigned int i = 0; i < queue_size; ++i) {
|
||||
for (int i = 0; i < queue_size; ++i) {
|
||||
CHECK_NOT_UPDATED(i);
|
||||
CHECK_COPY(u.val, queue_size + overflow_by - 1);
|
||||
}
|
||||
@@ -717,7 +717,7 @@ int uORBTest::UnitTest::pub_test_queue_main()
|
||||
{
|
||||
struct orb_test_medium t;
|
||||
orb_advert_t ptopic;
|
||||
const unsigned int queue_size = 50;
|
||||
const int queue_size = 50;
|
||||
t.val = 0;
|
||||
|
||||
if ((ptopic = orb_advertise_queue(ORB_ID(orb_test_medium_queue_poll), &t, queue_size)) == nullptr) {
|
||||
|
||||
@@ -71,7 +71,6 @@ px4_add_module(
|
||||
COMPILE_FLAGS
|
||||
-Wno-deprecated-declarations
|
||||
-O3
|
||||
-Wno-sign-compare
|
||||
SRCS
|
||||
uavcanesc_main.cpp
|
||||
indication_controller.cpp
|
||||
|
||||
@@ -167,7 +167,7 @@ using ::isfinite;
|
||||
/* FIXME - Used to satisfy build */
|
||||
#define getreg32(a) (*(volatile uint32_t *)(a))
|
||||
|
||||
#define USEC_PER_TICK (1000000UL/PX4_TICKS_PER_SEC)
|
||||
#define USEC_PER_TICK (1000000/PX4_TICKS_PER_SEC)
|
||||
#define USEC2TICK(x) (((x)+(USEC_PER_TICK/2))/USEC_PER_TICK)
|
||||
|
||||
#define px4_statfs_buf_f_bavail_t unsigned long
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user