From ab99ea54eb237d742262c8e9bf9c36474e4f4e27 Mon Sep 17 00:00:00 2001 From: murata Date: Sat, 29 Oct 2016 07:10:03 +0900 Subject: [PATCH] Plane: To nullptr from NULL. --- ArduPlane/ArduPlane.cpp | 2 +- ArduPlane/GCS_Mavlink.cpp | 6 +++--- ArduPlane/geofence.cpp | 30 +++++++++++++++--------------- ArduPlane/px4_mixer.cpp | 8 ++++---- ArduPlane/servos.cpp | 2 +- ArduPlane/system.cpp | 8 ++++---- ArduPlane/tuning.cpp | 2 +- 7 files changed, 29 insertions(+), 29 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index f5cf39334a..e6dc55a0bb 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -236,7 +236,7 @@ void Plane::update_compass(void) DataFlash.Log_Write_Compass(compass); } } else { - ahrs.set_compass(NULL); + ahrs.set_compass(nullptr); } } diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index cec0961bd6..f4db60902c 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -976,7 +976,7 @@ GCS_MAVLINK_Plane::data_stream_send(void) handle_log_send(plane.DataFlash); } - if (_queued_parameter != NULL) { + if (_queued_parameter != nullptr) { if (streamRates[STREAM_PARAMS].get() <= 0) { streamRates[STREAM_PARAMS].set(10); } @@ -2373,9 +2373,9 @@ void Plane::gcs_update(void) for (uint8_t i=0; iboundary_uptodate = false; } } @@ -92,22 +92,22 @@ void Plane::geofence_load(void) { uint8_t i; - if (geofence_state == NULL) { + if (geofence_state == nullptr) { uint16_t boundary_size = sizeof(Vector2l) * max_fencepoints(); if (hal.util->available_memory() < 100 + boundary_size + sizeof(struct GeofenceState)) { // too risky to enable as we could run out of stack goto failed; } geofence_state = (struct GeofenceState *)calloc(1, sizeof(struct GeofenceState)); - if (geofence_state == NULL) { + if (geofence_state == nullptr) { // not much we can do here except disable it goto failed; } geofence_state->boundary = (Vector2l *)calloc(1, boundary_size); - if (geofence_state->boundary == NULL) { + if (geofence_state->boundary == nullptr) { free(geofence_state); - geofence_state = NULL; + geofence_state = nullptr; goto failed; } @@ -170,13 +170,13 @@ void Plane::geofence_update_pwm_enabled_state() } else { is_pwm_enabled = (hal.rcin->read(g.fence_channel-1) > FENCE_ENABLE_PWM); } - if (is_pwm_enabled && geofence_state == NULL) { + if (is_pwm_enabled && geofence_state == nullptr) { // we need to load the fence geofence_load(); return; } - if (geofence_state == NULL) { + if (geofence_state == nullptr) { // not loaded return; } @@ -192,10 +192,10 @@ void Plane::geofence_update_pwm_enabled_state() //return true on success, false on failure bool Plane::geofence_set_enabled(bool enable, GeofenceEnableReason r) { - if (geofence_state == NULL && enable) { + if (geofence_state == nullptr && enable) { geofence_load(); } - if (geofence_state == NULL) { + if (geofence_state == nullptr) { return false; } @@ -216,7 +216,7 @@ bool Plane::geofence_enabled(void) { geofence_update_pwm_enabled_state(); - if (geofence_state == NULL) { + if (geofence_state == nullptr) { return false; } @@ -237,7 +237,7 @@ bool Plane::geofence_enabled(void) * Return false on failure to set floor state. */ bool Plane::geofence_set_floor_enabled(bool floor_enable) { - if (geofence_state == NULL) { + if (geofence_state == nullptr) { return false; } @@ -282,7 +282,7 @@ void Plane::geofence_check(bool altitude_check_only) if (!geofence_enabled()) { // switch back to the chosen control mode if still in // GUIDED to the return point - if (geofence_state != NULL && + if (geofence_state != nullptr && (g.fence_action == FENCE_ACTION_GUIDED || g.fence_action == FENCE_ACTION_GUIDED_THR_PASS || g.fence_action == FENCE_ACTION_RTL) && (control_mode == GUIDED || control_mode == AVOID_ADSB) && geofence_present() && @@ -297,7 +297,7 @@ void Plane::geofence_check(bool altitude_check_only) } /* allocate the geo-fence state if need be */ - if (geofence_state == NULL || !geofence_state->boundary_uptodate) { + if (geofence_state == nullptr || !geofence_state->boundary_uptodate) { geofence_load(); if (!geofence_enabled()) { // may have been disabled by load @@ -429,7 +429,7 @@ void Plane::geofence_check(bool altitude_check_only) */ bool Plane::geofence_stickmixing(void) { if (geofence_enabled() && - geofence_state != NULL && + geofence_state != nullptr && geofence_state->fence_triggered && (control_mode == GUIDED || control_mode == AVOID_ADSB)) { // don't mix in user input @@ -444,7 +444,7 @@ bool Plane::geofence_stickmixing(void) { */ void Plane::geofence_send_status(mavlink_channel_t chan) { - if (geofence_enabled() && geofence_state != NULL) { + if (geofence_enabled() && geofence_state != nullptr) { mavlink_msg_fence_status_send(chan, (int8_t)geofence_state->fence_triggered, geofence_state->breach_count, diff --git a/ArduPlane/px4_mixer.cpp b/ArduPlane/px4_mixer.cpp index 7f983b85fa..3b5a5f7f83 100644 --- a/ArduPlane/px4_mixer.cpp +++ b/ArduPlane/px4_mixer.cpp @@ -231,7 +231,7 @@ bool Plane::setup_failsafe_mixing(void) { const char *mixer_filename = "/fs/microsd/APM/MIXER.MIX"; bool ret = false; - char *buf = NULL; + char *buf = nullptr; const uint16_t buf_size = 2048; uint16_t fileSize, new_crc; int px4io_fd = -1; @@ -240,7 +240,7 @@ bool Plane::setup_failsafe_mixing(void) unsigned mixer_status = 0; buf = (char *)malloc(buf_size); - if (buf == NULL) { + if (buf == nullptr) { goto failed; } @@ -295,7 +295,7 @@ bool Plane::setup_failsafe_mixing(void) // a RC config limitation in px4io.c limiting to PX4IO_RC_MAPPED_CONTROL_CHANNELS for (uint8_t i=0; i<8; i++) { RC_Channel *ch = RC_Channel::rc_channel(i); - if (ch == NULL) { + if (ch == nullptr) { continue; } struct pwm_output_rc_config config; @@ -398,7 +398,7 @@ bool Plane::setup_failsafe_mixing(void) ret = true; failed: - if (buf != NULL) { + if (buf != nullptr) { free(buf); } if (px4io_fd != -1) { diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index 8cc75575bb..d4c6000d48 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -535,7 +535,7 @@ void Plane::set_servos_flaps(void) // work out any manual flap input RC_Channel *flapin = RC_Channel::rc_channel(g.flapin_channel-1); - if (flapin != NULL && !failsafe.ch3_failsafe && failsafe.ch3_counter == 0) { + if (flapin != nullptr && !failsafe.ch3_failsafe && failsafe.ch3_counter == 0) { flapin->input(); manual_flap_percent = flapin->percent_input(); } diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index ff376b1e48..a9eb8e3481 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -46,10 +46,10 @@ int8_t Plane::reboot_board(uint8_t argc, const Menu::arg *argv) void Plane::run_cli(AP_HAL::UARTDriver *port) { // disable the failsafe code in the CLI - hal.scheduler->register_timer_failsafe(NULL,1); + hal.scheduler->register_timer_failsafe(nullptr,1); // disable the mavlink delay callback - hal.scheduler->register_delay_callback(NULL, 5); + hal.scheduler->register_delay_callback(nullptr, 5); cliSerial = port; Menu::set_port(port); @@ -227,10 +227,10 @@ void Plane::init_ardupilot() if (g.cli_enabled == 1) { const char *msg = "\nPress ENTER 3 times to start interactive setup\n"; cliSerial->println(msg); - if (gcs[1].initialised && (gcs[1].get_uart() != NULL)) { + if (gcs[1].initialised && (gcs[1].get_uart() != nullptr)) { gcs[1].get_uart()->println(msg); } - if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != NULL)) { + if (num_gcs > 2 && gcs[2].initialised && (gcs[2].get_uart() != nullptr)) { gcs[2].get_uart()->println(msg); } } diff --git a/ArduPlane/tuning.cpp b/ArduPlane/tuning.cpp index ed8027a9b6..1058d7e18a 100644 --- a/ArduPlane/tuning.cpp +++ b/ArduPlane/tuning.cpp @@ -85,7 +85,7 @@ const AP_Tuning_Plane::tuning_name AP_Tuning_Plane::tuning_names[] = { }; /* - get a pointer to an AP_Float for a parameter, or NULL on fail + get a pointer to an AP_Float for a parameter, or nullptr on fail */ AP_Float *AP_Tuning_Plane::get_param_pointer(uint8_t parm) {