From 10c20b38ad80feb4b3d2510c4b2bb48319717d56 Mon Sep 17 00:00:00 2001 From: Mara Bos <m-ou.se@m-ou.se> Date: Sat, 27 Oct 2018 10:56:58 +0200 Subject: [PATCH] Fix many format strings. Fixes these invalid format strings: - A `%d` for a pointer (replaced it by `%p`) - A 0x%08x (and a 0x%0x8!) for a pointer (replaced by %p) - 2 cases of `%d` for a `ssize_t` (replaced it by `%zi`) - 1 case of a %u for an `int` (replaced by %i) - 3 cases of %d for a `long` (replaced by %ld) - 19 cases of `%d`, `%i`, `%u` or `%lu` for a `size_t` (replaced it by `%zu`) - An unused formatting argument (removed it) - A missing `%d` (added it) - A missing `%s` (added it) - 2 cases of `%llu` for a `uint64_t` (replaced it by `"%" PRIu64`) - 6 cases of giving a string directly as format string (replaced it by `("%s", string)`) - 2 cases of %*-s, which should probably have been %-*s. (Looks like NuttX accepts (the invalid) %*-s, but other platforms don't.) - A %04x for a `uint32_t` (replaced by "%04" PRIx32) --- platforms/posix/src/px4_daemon/client.cpp | 2 +- src/drivers/batt_smbus/batt_smbus_main.cpp | 2 +- src/drivers/distance_sensor/sf0x/sf0x.cpp | 2 +- src/drivers/distance_sensor/tfmini/tfmini.cpp | 2 +- src/drivers/px4io/px4io.cpp | 2 +- .../telemetry/frsky_telemetry/frsky_telemetry.cpp | 6 +++--- src/examples/bottle_drop/bottle_drop.cpp | 2 +- src/lib/rc/rc_tests/RCTest.cpp | 2 +- src/modules/commander/Commander.cpp | 4 ++-- src/modules/commander/airspeed_calibration.cpp | 2 +- src/modules/commander/mag_calibration.cpp | 2 +- .../BlockLocalPositionEstimator.cpp | 10 +++++----- src/modules/mavlink/mavlink_main.cpp | 8 ++++---- src/modules/mc_pos_control/mc_pos_control_main.cpp | 2 +- .../navigator/mission_feasibility_checker.cpp | 10 +++++----- src/modules/uORB/uORBDeviceMaster.cpp | 12 ++---------- src/modules/uORB/uORBDeviceNode.cpp | 2 +- src/systemcmds/bl_update/bl_update.c | 8 ++++---- src/systemcmds/tests/test_dataman.c | 2 +- 19 files changed, 37 insertions(+), 45 deletions(-) diff --git a/platforms/posix/src/px4_daemon/client.cpp b/platforms/posix/src/px4_daemon/client.cpp index 560475c8e3..5f76cf1a6b 100644 --- a/platforms/posix/src/px4_daemon/client.cpp +++ b/platforms/posix/src/px4_daemon/client.cpp @@ -293,7 +293,7 @@ Client::_stdout_msg_packet(const client_recv_packet_s &packet) return 0; } else { - PX4_ERR("payload size wrong (%i > %i)", packet.header.payload_length, sizeof(packet.payload.stdout_msg.text)); + PX4_ERR("payload size wrong (%i > %zu)", packet.header.payload_length, sizeof(packet.payload.stdout_msg.text)); return -1; } } diff --git a/src/drivers/batt_smbus/batt_smbus_main.cpp b/src/drivers/batt_smbus/batt_smbus_main.cpp index cafb34874e..76378b4242 100644 --- a/src/drivers/batt_smbus/batt_smbus_main.cpp +++ b/src/drivers/batt_smbus/batt_smbus_main.cpp @@ -128,7 +128,7 @@ int start(enum BATT_SMBUS_BUS busid) if (busid == BATT_SMBUS_BUS_ALL && bus_options[i].dev != nullptr) { // This device is already started. - PX4_INFO("Smart battery %d already started", bus_options[i].dev); + PX4_INFO("Smart battery %p already started", bus_options[i].dev); continue; } diff --git a/src/drivers/distance_sensor/sf0x/sf0x.cpp b/src/drivers/distance_sensor/sf0x/sf0x.cpp index 343cc57be6..8ca3f7e502 100644 --- a/src/drivers/distance_sensor/sf0x/sf0x.cpp +++ b/src/drivers/distance_sensor/sf0x/sf0x.cpp @@ -853,7 +853,7 @@ test() sz = read(fd, &report, sizeof(report)); if (sz != sizeof(report)) { - PX4_ERR("read failed: got %d vs exp. %d", sz, sizeof(report)); + PX4_ERR("read failed: got %zi vs exp. %zu", sz, sizeof(report)); break; } diff --git a/src/drivers/distance_sensor/tfmini/tfmini.cpp b/src/drivers/distance_sensor/tfmini/tfmini.cpp index 151b522b0b..8a1ccb5a0f 100644 --- a/src/drivers/distance_sensor/tfmini/tfmini.cpp +++ b/src/drivers/distance_sensor/tfmini/tfmini.cpp @@ -822,7 +822,7 @@ test() sz = px4_read(fd, &report, sizeof(report)); if (sz != sizeof(report)) { - PX4_ERR("read failed: got %d vs exp. %d", sz, sizeof(report)); + PX4_ERR("read failed: got %zi vs exp. %zu", sz, sizeof(report)); break; } diff --git a/src/drivers/px4io/px4io.cpp b/src/drivers/px4io/px4io.cpp index ed55d47393..2a65cf0215 100644 --- a/src/drivers/px4io/px4io.cpp +++ b/src/drivers/px4io/px4io.cpp @@ -3182,7 +3182,7 @@ test(void) ret = write(fd, servos, sizeof(servos)); if (ret != (int)sizeof(servos)) { - err(1, "error writing PWM servo data, wrote %lu got %d", sizeof(servos), ret); + err(1, "error writing PWM servo data, wrote %zu got %d", sizeof(servos), ret); } if (direction > 0) { diff --git a/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp b/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp index f5cdb782cd..89e3f27260 100644 --- a/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp +++ b/src/drivers/telemetry/frsky_telemetry/frsky_telemetry.cpp @@ -778,19 +778,19 @@ int frsky_telemetry_main(int argc, char *argv[]) case SPORT: PX4_INFO("running: SPORT"); PX4_INFO("port: %s", device_name); - PX4_INFO("packets sent: %d", sentPackets); + PX4_INFO("packets sent: %ld", sentPackets); break; case SPORT_SINGLE_WIRE: PX4_INFO("running: SPORT (single wire)"); PX4_INFO("port: %s", device_name); - PX4_INFO("packets sent: %d", sentPackets); + PX4_INFO("packets sent: %ld", sentPackets); break; case DTYPE: PX4_INFO("running: DTYPE"); PX4_INFO("port: %s", device_name); - PX4_INFO("packets sent: %d", sentPackets); + PX4_INFO("packets sent: %ld", sentPackets); break; } diff --git a/src/examples/bottle_drop/bottle_drop.cpp b/src/examples/bottle_drop/bottle_drop.cpp index e8f4dca07e..165eb5ae6a 100644 --- a/src/examples/bottle_drop/bottle_drop.cpp +++ b/src/examples/bottle_drop/bottle_drop.cpp @@ -638,7 +638,7 @@ BottleDrop::task_main() float approach_direction = get_bearing_to_next_waypoint(flight_vector_s.lat, flight_vector_s.lon, flight_vector_e.lat, flight_vector_e.lon); - mavlink_log_critical(&_mavlink_log_pub, "position set, approach heading: %u", (unsigned)distance_real, + mavlink_log_critical(&_mavlink_log_pub, "position set, approach heading: %u", (unsigned)math::degrees(approach_direction + M_PI_F)); _drop_state = DROP_STATE_TARGET_SET; diff --git a/src/lib/rc/rc_tests/RCTest.cpp b/src/lib/rc/rc_tests/RCTest.cpp index 06b031ffe8..ba6fba2046 100644 --- a/src/lib/rc/rc_tests/RCTest.cpp +++ b/src/lib/rc/rc_tests/RCTest.cpp @@ -122,7 +122,7 @@ bool RCTest::crsfTest() } if (expected_num_channels != num_values) { - PX4_ERR("File line: ", line_counter); + PX4_ERR("File line: %d", line_counter); ut_compare("Unexpected number of decoded channels", expected_num_channels, num_values); } diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 9a14e139c4..53fc25f1ad 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -2108,7 +2108,7 @@ Commander::run() } else { if (!status_flags.rc_input_blocked && !status.rc_signal_lost) { - mavlink_log_critical(&mavlink_log_pub, "MANUAL CONTROL LOST (at t=%llums)", hrt_absolute_time() / 1000); + mavlink_log_critical(&mavlink_log_pub, "MANUAL CONTROL LOST (at t=%" PRIu64 "ms)", hrt_absolute_time() / 1000); status.rc_signal_lost = true; rc_signal_lost_timestamp = sp_man.timestamp; set_health_flags(subsystem_info_s::SUBSYSTEM_TYPE_RCRECEIVER, true, true, false, status); @@ -3401,7 +3401,7 @@ print_reject_arm(const char *msg) if (t - last_print_mode_reject_time > PRINT_MODE_REJECT_INTERVAL) { last_print_mode_reject_time = t; - mavlink_log_critical(&mavlink_log_pub, msg); + mavlink_log_critical(&mavlink_log_pub, "%s", msg); tune_negative(true); } } diff --git a/src/modules/commander/airspeed_calibration.cpp b/src/modules/commander/airspeed_calibration.cpp index 75beac5c37..93d61bc3c0 100644 --- a/src/modules/commander/airspeed_calibration.cpp +++ b/src/modules/commander/airspeed_calibration.cpp @@ -143,7 +143,7 @@ int do_airspeed_calibration(orb_advert_t *mavlink_log_pub) /* any differential pressure failure a reason to abort */ if (diff_pres.error_count != 0) { - calibration_log_critical(mavlink_log_pub, "[cal] Airspeed sensor is reporting errors (%llu)", diff_pres.error_count); + calibration_log_critical(mavlink_log_pub, "[cal] Airspeed sensor is reporting errors (%" PRIu64 ")", diff_pres.error_count); calibration_log_critical(mavlink_log_pub, "[cal] Check your wiring before trying again"); feedback_calibration_failed(mavlink_log_pub); goto error_return; diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp index b6ee8f18fd..ba30f3cdea 100644 --- a/src/modules/commander/mag_calibration.cpp +++ b/src/modules/commander/mag_calibration.cpp @@ -307,7 +307,7 @@ static calibrate_return check_calibration_result(float offset_x, float offset_y, for (unsigned i = 0; i < num_finite; ++i) { if (!PX4_ISFINITE(must_be_finite[i])) { calibration_log_emergency(mavlink_log_pub, - "ERROR: Retry calibration (sphere NaN, #%u)", cur_mag); + "ERROR: Retry calibration (sphere NaN, #%zu)", cur_mag); return calibrate_return_error; } } diff --git a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp index 9e946c6f47..14ff7a05d6 100644 --- a/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp +++ b/src/modules/local_position_estimator/BlockLocalPositionEstimator.cpp @@ -222,13 +222,13 @@ void BlockLocalPositionEstimator::update() s->get().orientation == distance_sensor_s::ROTATION_DOWNWARD_FACING && _sub_lidar == nullptr) { _sub_lidar = s; - mavlink_and_console_log_info(&mavlink_log_pub, "%sDownward-facing Lidar detected with ID %i", msg_label, i); + mavlink_and_console_log_info(&mavlink_log_pub, "%sDownward-facing Lidar detected with ID %zu", msg_label, i); } else if (s->get().type == distance_sensor_s::MAV_DISTANCE_SENSOR_ULTRASOUND && s->get().orientation == distance_sensor_s::ROTATION_DOWNWARD_FACING && _sub_sonar == nullptr) { _sub_sonar = s; - mavlink_and_console_log_info(&mavlink_log_pub, "%sDownward-facing Sonar detected with ID %i", msg_label, i); + mavlink_and_console_log_info(&mavlink_log_pub, "%sDownward-facing Sonar detected with ID %zu", msg_label, i); } } } @@ -373,7 +373,7 @@ void BlockLocalPositionEstimator::update() // don't want it to take too long if (!PX4_ISFINITE(_x(i))) { reinit_x = true; - mavlink_and_console_log_info(&mavlink_log_pub, "%sreinit x, x(%d) not finite", msg_label, i); + mavlink_and_console_log_info(&mavlink_log_pub, "%sreinit x, x(%zu) not finite", msg_label, i); break; } } @@ -393,7 +393,7 @@ void BlockLocalPositionEstimator::update() for (size_t j = 0; j <= i; j++) { if (!PX4_ISFINITE(_P(i, j))) { mavlink_and_console_log_info(&mavlink_log_pub, - "%sreinit P (%d, %d) not finite", msg_label, i, j); + "%sreinit P (%zu, %zu) not finite", msg_label, i, j); reinit_P = true; } @@ -401,7 +401,7 @@ void BlockLocalPositionEstimator::update() // make sure diagonal elements are positive if (_P(i, i) <= 0) { mavlink_and_console_log_info(&mavlink_log_pub, - "%sreinit P (%d, %d) negative", msg_label, i, j); + "%sreinit P (%zu, %zu) negative", msg_label, i, j); reinit_P = true; } diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 9bc04b4c72..eebf92e685 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1271,20 +1271,20 @@ Mavlink::handle_message(const mavlink_message_t *msg) void Mavlink::send_statustext_info(const char *string) { - mavlink_log_info(&_mavlink_log_pub, string); + mavlink_log_info(&_mavlink_log_pub, "%s", string); } void Mavlink::send_statustext_critical(const char *string) { - mavlink_log_critical(&_mavlink_log_pub, string); - PX4_ERR(string); + mavlink_log_critical(&_mavlink_log_pub, "%s", string); + PX4_ERR("%s", string); } void Mavlink::send_statustext_emergency(const char *string) { - mavlink_log_emergency(&_mavlink_log_pub, string); + mavlink_log_emergency(&_mavlink_log_pub, "%s", string); } void Mavlink::send_autopilot_capabilites() diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index ca222093bc..a20af184d0 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -351,7 +351,7 @@ MulticopterPositionControl::warn_rate_limited(const char *string) hrt_abstime now = hrt_absolute_time(); if (now - _last_warn > 200000) { - PX4_WARN(string); + PX4_WARN("%s", string); _last_warn = now; } } diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp index 1495b5e29a..893eb0b6dc 100644 --- a/src/modules/navigator/mission_feasibility_checker.cpp +++ b/src/modules/navigator/mission_feasibility_checker.cpp @@ -170,7 +170,7 @@ MissionFeasibilityChecker::checkGeofence(const mission_s &mission, float home_al if (MissionBlock::item_contains_position(missionitem) && !_navigator->get_geofence().check(missionitem)) { - mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Geofence violation for waypoint %d", i + 1); + mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Geofence violation for waypoint %zu", i + 1); return false; } } @@ -200,11 +200,11 @@ MissionFeasibilityChecker::checkHomePositionAltitude(const mission_s &mission, f _navigator->get_mission_result()->warning = true; if (throw_error) { - mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Mission rejected: No home pos, WP %d uses rel alt", i + 1); + mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Mission rejected: No home pos, WP %zu uses rel alt", i + 1); return false; } else { - mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Warning: No home pos, WP %d uses rel alt", i + 1); + mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Warning: No home pos, WP %zu uses rel alt", i + 1); return true; } } @@ -217,11 +217,11 @@ MissionFeasibilityChecker::checkHomePositionAltitude(const mission_s &mission, f _navigator->get_mission_result()->warning = true; if (throw_error) { - mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Mission rejected: Waypoint %d below home", i + 1); + mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Mission rejected: Waypoint %zu below home", i + 1); return false; } else { - mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Warning: Waypoint %d below home", i + 1); + mavlink_log_critical(_navigator->get_mavlink_log_pub(), "Warning: Waypoint %zu below home", i + 1); return true; } } diff --git a/src/modules/uORB/uORBDeviceMaster.cpp b/src/modules/uORB/uORBDeviceMaster.cpp index 0684dee16e..afccdc8e93 100644 --- a/src/modules/uORB/uORBDeviceMaster.cpp +++ b/src/modules/uORB/uORBDeviceMaster.cpp @@ -367,21 +367,13 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters) PX4_INFO_RAW("\033[H"); // move cursor home and clear screen PX4_INFO_RAW(CLEAR_LINE "update: 1s, num topics: %i\n", num_topics); -#ifdef __PX4_NUTTX - PX4_INFO_RAW(CLEAR_LINE "%*-s INST #SUB #MSG #LOST #QSIZE\n", (int)max_topic_name_length - 2, "TOPIC NAME"); -#else - PX4_INFO_RAW(CLEAR_LINE "%*s INST #SUB #MSG #LOST #QSIZE\n", -(int)max_topic_name_length + 2, "TOPIC NAME"); -#endif + PX4_INFO_RAW(CLEAR_LINE "%-*s INST #SUB #MSG #LOST #QSIZE\n", (int)max_topic_name_length - 2, "TOPIC NAME"); cur_node = first_node; while (cur_node) { if (!print_active_only || cur_node->pub_msg_delta > 0) { -#ifdef __PX4_NUTTX - PX4_INFO_RAW(CLEAR_LINE "%*-s %2i %4i %4i %5i %i\n", (int)max_topic_name_length, -#else - PX4_INFO_RAW(CLEAR_LINE "%*s %2i %4i %4i %5i %i\n", -(int)max_topic_name_length, -#endif + PX4_INFO_RAW(CLEAR_LINE "%-*s %2i %4i %4i %5i %i\n", (int)max_topic_name_length, cur_node->node->get_meta()->o_name, (int)cur_node->instance, (int)cur_node->node->subscriber_count(), cur_node->pub_msg_delta, (int)cur_node->lost_msg_delta, cur_node->node->get_queue_size()); diff --git a/src/modules/uORB/uORBDeviceNode.cpp b/src/modules/uORB/uORBDeviceNode.cpp index 36699e3cc5..21702bcc2d 100644 --- a/src/modules/uORB/uORBDeviceNode.cpp +++ b/src/modules/uORB/uORBDeviceNode.cpp @@ -760,7 +760,7 @@ int16_t uORB::DeviceNode::process_received_message(int32_t length, uint8_t *data int16_t ret = -1; if (length != (int32_t)(_meta->o_size)) { - PX4_ERR("Received DataLength[%d] != ExpectedLen[%d]", _meta->o_name, (int)length, (int)_meta->o_size); + PX4_ERR("Received '%s' with DataLength[%d] != ExpectedLen[%d]", _meta->o_name, (int)length, (int)_meta->o_size); return PX4_ERROR; } diff --git a/src/systemcmds/bl_update/bl_update.c b/src/systemcmds/bl_update/bl_update.c index 6a3b5e51ae..b7b924b374 100644 --- a/src/systemcmds/bl_update/bl_update.c +++ b/src/systemcmds/bl_update/bl_update.c @@ -166,7 +166,7 @@ bl_update_main(int argc, char *argv[]) if (size != BL_FILE_SIZE_LIMIT) { - PX4_ERR("erase error at 0x%08x", &base[size]); + PX4_ERR("erase error at %p", &base[size]); } PX4_INFO("flashing..."); @@ -177,7 +177,7 @@ bl_update_main(int argc, char *argv[]) if (size != s.st_size) { - PX4_ERR("program error at 0x%0x8", &base[size]); + PX4_ERR("program error at %p", &base[size]); goto flash_end; } @@ -191,7 +191,7 @@ bl_update_main(int argc, char *argv[]) for (int i = 0; i < s.st_size; i++) { if (base[i] != buf[i]) { - PX4_WARN("verify failed at %u - retry update, DO NOT reboot", i); + PX4_WARN("verify failed at %i - retry update, DO NOT reboot", i); goto flash_end; } } @@ -239,7 +239,7 @@ setopt(void) return 0; } - PX4_ERR("option bits setting failed; readback 0x%04x", *optcr); + PX4_ERR("option bits setting failed; readback 0x%04" PRIx32, *optcr); return 1; } #endif // CONFIG_STM32_STM32F4XXX diff --git a/src/systemcmds/tests/test_dataman.c b/src/systemcmds/tests/test_dataman.c index 539f6de364..10668d99d7 100644 --- a/src/systemcmds/tests/test_dataman.c +++ b/src/systemcmds/tests/test_dataman.c @@ -143,7 +143,7 @@ task_main(int argc, char *argv[]) } hrt_abstime rend = hrt_absolute_time(); - PX4_INFO("task %d pass, hit %d, miss %d, io time read %llums. write %llums.", + PX4_INFO("task %d pass, hit %d, miss %d, io time read %" PRIu64 "ms. write %" PRIu64 "ms.", my_id, hit, miss, (rend - rstart) / NUM_MISSIONS_TEST / 1000, (wend - wstart) / NUM_MISSIONS_TEST / 1000); px4_sem_post(sems + my_id); return 0; -- GitLab