From c808ee2f497e7a7a6d570632a3224e655b377323 Mon Sep 17 00:00:00 2001 From: murata Date: Sun, 30 Oct 2016 14:24:21 +0900 Subject: [PATCH] Global: To nullptr from NULL. RC_Channel: To nullptr from NULL. AC_Fence: To nullptr from NULL. AC_Avoidance: To nullptr from NULL. AC_PrecLand: To nullptr from NULL. DataFlash: To nullptr from NULL. SITL: To nullptr from NULL. GCS_MAVLink: To nullptr from NULL. DataFlash: To nullptr from NULL. AP_Compass: To nullptr from NULL. Global: To nullptr from NULL. Global: To nullptr from NULL. --- libraries/AC_Avoidance/AC_Avoid.cpp | 2 +- libraries/AC_Fence/AC_Fence.cpp | 4 +- libraries/AC_Fence/AC_Fence.h | 2 +- libraries/AC_Fence/AC_PolyFence_loader.cpp | 12 +- libraries/AC_Fence/AC_PolyFence_loader.h | 2 +- libraries/AC_PrecLand/AC_PrecLand.cpp | 12 +- libraries/AC_WPNav/AC_WPNav.cpp | 4 +- libraries/AC_WPNav/AC_WPNav.h | 4 +- libraries/AP_AHRS/AP_AHRS.h | 10 +- .../AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp | 2 +- libraries/AP_AccelCal/AP_AccelCal.cpp | 14 +- libraries/AP_AccelCal/AccelCalibrator.cpp | 16 +- libraries/AP_Airspeed/AP_Airspeed_analog.cpp | 2 +- libraries/AP_Airspeed/AP_Airspeed_analog.h | 2 +- libraries/AP_Arming/AP_Arming.cpp | 2 +- libraries/AP_Avoidance/AP_Avoidance.cpp | 4 +- libraries/AP_Baro/AP_Baro.cpp | 2 +- libraries/AP_BattMonitor/AP_BattMonitor.cpp | 8 +- libraries/AP_BoardConfig/px4_drivers.cpp | 2 +- libraries/AP_Common/Location.cpp | 12 +- libraries/AP_Compass/AP_Compass.cpp | 2 +- libraries/AP_Compass/AP_Compass_HIL.cpp | 6 +- libraries/AP_Compass/AP_Compass_PX4.cpp | 6 +- libraries/AP_Compass/AP_Compass_QURT.cpp | 6 +- libraries/AP_Compass/AP_Compass_qflight.cpp | 6 +- libraries/AP_Compass/CompassCalibrator.cpp | 28 ++-- libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp | 2 +- libraries/AP_GPS/AP_GPS.cpp | 34 ++-- libraries/AP_GPS/AP_GPS_NMEA.cpp | 6 +- libraries/AP_GPS/AP_GPS_SBF.cpp | 2 +- libraries/AP_GPS/AP_GPS_SBP.cpp | 4 +- libraries/AP_GPS/AP_GPS_UBLOX.cpp | 22 +-- .../examples/GPS_AUTO_test/GPS_AUTO_test.cpp | 2 +- libraries/AP_HAL/AP_HAL_Boards.h | 2 +- libraries/AP_HAL/Util.cpp | 2 +- libraries/AP_HAL/Util.h | 8 +- .../AP_HAL/examples/UART_test/UART_test.cpp | 4 +- libraries/AP_HAL/utility/RingBuffer.h | 2 +- libraries/AP_HAL/utility/Socket.cpp | 10 +- libraries/AP_HAL/utility/dsm.cpp | 2 +- libraries/AP_HAL/utility/getopt_cpp.cpp | 10 +- libraries/AP_HAL/utility/srxl.cpp | 2 +- libraries/AP_HAL_Empty/HAL_Empty_Class.cpp | 6 +- libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp | 6 +- libraries/AP_HAL_Linux/AnalogIn_Raspilot.cpp | 6 +- .../AP_HAL_Linux/CameraSensor_Mt9v117.cpp | 2 +- libraries/AP_HAL_Linux/GPIO_RPI.cpp | 2 +- .../AP_HAL_Linux/OpticalFlow_Onboard.cpp | 10 +- libraries/AP_HAL_Linux/PWM_Sysfs.cpp | 6 +- libraries/AP_HAL_Linux/PWM_Sysfs.h | 10 +- libraries/AP_HAL_Linux/RCInput.cpp | 2 +- libraries/AP_HAL_Linux/RCInput_115200.cpp | 2 +- libraries/AP_HAL_Linux/RCInput_RPI.cpp | 10 +- libraries/AP_HAL_Linux/RCInput_SBUS.cpp | 2 +- libraries/AP_HAL_Linux/RCOutput_Bebop.cpp | 4 +- libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp | 2 +- libraries/AP_HAL_Linux/RPIOUARTDriver.cpp | 2 +- libraries/AP_HAL_Linux/SPIUARTDriver.cpp | 6 +- libraries/AP_HAL_Linux/Scheduler.cpp | 2 +- libraries/AP_HAL_Linux/Semaphores.h | 2 +- libraries/AP_HAL_Linux/TCPServerDevice.cpp | 20 +-- libraries/AP_HAL_Linux/TCPServerDevice.h | 2 +- libraries/AP_HAL_Linux/ToneAlarm_Raspilot.cpp | 4 +- libraries/AP_HAL_Linux/UARTDriver.cpp | 24 +-- libraries/AP_HAL_Linux/Util.cpp | 8 +- libraries/AP_HAL_Linux/Util.h | 4 +- libraries/AP_HAL_Linux/VideoIn.cpp | 4 +- .../examples/GPIOTest/GPIOTest.cpp | 4 +- .../AP_HAL_Linux/qflight/dsp_functions.cpp | 6 +- libraries/AP_HAL_PX4/AnalogIn.cpp | 12 +- libraries/AP_HAL_PX4/HAL_PX4_Class.cpp | 6 +- libraries/AP_HAL_PX4/NSHShellStream.cpp | 2 +- libraries/AP_HAL_PX4/RCInput.cpp | 2 +- libraries/AP_HAL_PX4/RCOutput.cpp | 8 +- libraries/AP_HAL_PX4/RCOutput.h | 4 +- libraries/AP_HAL_PX4/Scheduler.cpp | 24 +-- libraries/AP_HAL_PX4/Semaphores.h | 2 +- libraries/AP_HAL_PX4/Util.cpp | 4 +- libraries/AP_HAL_QURT/HAL_QURT_Class.cpp | 4 +- libraries/AP_HAL_QURT/Scheduler.cpp | 8 +- libraries/AP_HAL_QURT/Semaphores.h | 2 +- libraries/AP_HAL_QURT/dsp_main.cpp | 2 +- libraries/AP_HAL_QURT/mainapp/getifaddrs.cpp | 40 ++--- libraries/AP_HAL_QURT/mainapp/mainapp.cpp | 6 +- libraries/AP_HAL_QURT/replace.cpp | 4 +- libraries/AP_HAL_SITL/SITL_State.cpp | 18 +-- libraries/AP_HAL_SITL/SITL_cmdline.cpp | 8 +- libraries/AP_HAL_SITL/Scheduler.cpp | 12 +- libraries/AP_HAL_SITL/Semaphores.h | 2 +- libraries/AP_HAL_SITL/UARTDriver.cpp | 14 +- libraries/AP_HAL_SITL/sitl_barometer.cpp | 2 +- libraries/AP_HAL_SITL/sitl_compass.cpp | 2 +- libraries/AP_HAL_SITL/sitl_gps.cpp | 4 +- libraries/AP_HAL_SITL/sitl_ins.cpp | 2 +- libraries/AP_HAL_SITL/system.cpp | 6 +- libraries/AP_HAL_VRBRAIN/AnalogIn.cpp | 8 +- .../AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp | 6 +- libraries/AP_HAL_VRBRAIN/NSHShellStream.cpp | 2 +- libraries/AP_HAL_VRBRAIN/RCInput.cpp | 2 +- libraries/AP_HAL_VRBRAIN/RCOutput.cpp | 8 +- libraries/AP_HAL_VRBRAIN/RCOutput.h | 4 +- libraries/AP_HAL_VRBRAIN/Scheduler.cpp | 24 +-- libraries/AP_HAL_VRBRAIN/Semaphores.h | 2 +- libraries/AP_HAL_VRBRAIN/Util.cpp | 4 +- .../AP_InertialSensor/AP_InertialSensor.cpp | 14 +- .../AP_InertialSensor/AP_InertialSensor.h | 2 +- .../AP_InertialSensor_Backend.cpp | 6 +- .../AP_InertialSensor_Backend.h | 2 +- .../AP_InertialSensor_HIL.cpp | 6 +- .../AP_InertialSensor_PX4.cpp | 6 +- .../AP_InertialSensor_QURT.cpp | 8 +- .../AP_InertialSensor_SITL.cpp | 6 +- ...AP_InertialSensor_UserInteract_MAVLink.cpp | 4 +- .../AP_InertialSensor_qflight.cpp | 6 +- libraries/AP_Math/matrix3.cpp | 6 +- libraries/AP_Menu/AP_Menu.cpp | 34 ++-- .../examples/ModuleTest/ModuleTest.cpp | 2 +- libraries/AP_Mount/AP_Mount.cpp | 30 ++-- libraries/AP_Mount/AP_Mount_Alexmos.h | 2 +- .../AP_Mount/AP_Mount_SToRM32_serial.cpp | 2 +- libraries/AP_Mount/AP_Mount_SoloGimbal.cpp | 2 +- libraries/AP_Mount/SoloGimbal.cpp | 4 +- libraries/AP_Mount/SoloGimbal_Parameters.cpp | 2 +- libraries/AP_NavEKF2/AP_NavEKF2_Buffer.h | 6 +- libraries/AP_OpticalFlow/OpticalFlow.cpp | 4 +- libraries/AP_OpticalFlow/OpticalFlow.h | 2 +- libraries/AP_Param/AP_Param.cpp | 152 +++++++++--------- libraries/AP_Param/AP_Param.h | 10 +- libraries/AP_Proximity/AP_Proximity.cpp | 8 +- libraries/AP_RPM/AP_RPM.cpp | 4 +- .../AP_RangeFinder/AP_RangeFinder_BBB_PRU.cpp | 4 +- .../AP_RangeFinder/AP_RangeFinder_Bebop.cpp | 10 +- .../AP_RangeFinder/AP_RangeFinder_analog.cpp | 4 +- libraries/AP_RangeFinder/RangeFinder.cpp | 12 +- .../AP_SerialManager/AP_SerialManager.cpp | 8 +- libraries/AP_SerialManager/AP_SerialManager.h | 2 +- libraries/AP_Terrain/AP_Terrain.h | 2 +- libraries/AP_Terrain/TerrainIO.cpp | 8 +- libraries/DataFlash/DFMessageWriter.cpp | 2 +- libraries/DataFlash/DataFlash_Backend.cpp | 4 +- libraries/DataFlash/DataFlash_Block.cpp | 2 +- libraries/DataFlash/DataFlash_File.cpp | 38 ++--- libraries/DataFlash/DataFlash_MAVLink.cpp | 54 +++---- libraries/DataFlash/DataFlash_SITL.h | 2 +- libraries/DataFlash/LogFile.cpp | 8 +- libraries/GCS_MAVLink/GCS_Common.cpp | 32 ++-- libraries/GCS_MAVLink/GCS_MAVLink.cpp | 4 +- libraries/GCS_MAVLink/GCS_Signing.cpp | 8 +- libraries/GCS_MAVLink/GCS_serial_control.cpp | 8 +- libraries/RC_Channel/RC_Channel.cpp | 8 +- libraries/RC_Channel/RC_Channel_aux.cpp | 4 +- libraries/RC_Channel/RC_Channel_aux.h | 2 +- libraries/SITL/SIM_Aircraft.cpp | 20 +-- libraries/SITL/SIM_CRRCSim.cpp | 2 +- libraries/SITL/SIM_FlightAxis.cpp | 6 +- libraries/SITL/SIM_Frame.cpp | 2 +- libraries/SITL/SIM_Helicopter.cpp | 2 +- libraries/SITL/SIM_JSBSim.cpp | 16 +- libraries/SITL/SIM_Multicopter.cpp | 4 +- libraries/SITL/SIM_Rover.cpp | 2 +- libraries/SITL/SIM_last_letter.cpp | 2 +- 161 files changed, 658 insertions(+), 658 deletions(-) diff --git a/libraries/AC_Avoidance/AC_Avoid.cpp b/libraries/AC_Avoidance/AC_Avoid.cpp index f76c1cfeb5..f3d5c0a83f 100644 --- a/libraries/AC_Avoidance/AC_Avoid.cpp +++ b/libraries/AC_Avoidance/AC_Avoid.cpp @@ -115,7 +115,7 @@ void AC_Avoid::adjust_velocity_poly(const float kP, const float accel_cmss, Vect Vector2f* boundary = _fence.get_polygon_points(num_points); // exit if there are no points - if (boundary == NULL || num_points == 0) { + if (boundary == nullptr || num_points == 0) { return; } diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index 17b1dfecf2..1fffaa7cdd 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -345,7 +345,7 @@ bool AC_Fence::boundary_breached(const Vector2f& location, uint16_t num_points, void AC_Fence::handle_msg(mavlink_channel_t chan, mavlink_message_t* msg) { // exit immediately if null message - if (msg == NULL) { + if (msg == nullptr) { return; } @@ -405,7 +405,7 @@ bool AC_Fence::load_polygon_from_eeprom(bool force_reload) } // exit if we could not allocate RAM for the boundary - if (_boundary == NULL) { + if (_boundary == nullptr) { return false; } diff --git a/libraries/AC_Fence/AC_Fence.h b/libraries/AC_Fence/AC_Fence.h index ede920cdf5..1605ae3bb6 100644 --- a/libraries/AC_Fence/AC_Fence.h +++ b/libraries/AC_Fence/AC_Fence.h @@ -156,7 +156,7 @@ private: // polygon fence variables AC_PolyFence_loader _poly_loader; // helper for loading/saving polygon points - Vector2f *_boundary = NULL; // array of boundary points. Note: point 0 is the return point + Vector2f *_boundary = nullptr; // array of boundary points. Note: point 0 is the return point uint8_t _boundary_num_points = 0; // number of points in the boundary array (should equal _total parameter after load has completed) bool _boundary_create_attempted = false; // true if we have attempted to create the boundary array bool _boundary_loaded = false; // true if boundary array has been loaded from eeprom diff --git a/libraries/AC_Fence/AC_PolyFence_loader.cpp b/libraries/AC_Fence/AC_PolyFence_loader.cpp index 0c62d94b85..d578d0953d 100644 --- a/libraries/AC_Fence/AC_PolyFence_loader.cpp +++ b/libraries/AC_Fence/AC_PolyFence_loader.cpp @@ -13,13 +13,13 @@ uint8_t AC_PolyFence_loader::max_points() const } // create buffer to hold copy of eeprom points in RAM -// returns NULL if not enough memory can be allocated +// returns nullptr if not enough memory can be allocated void* AC_PolyFence_loader::create_point_array(uint8_t element_size) { uint32_t array_size = max_points() * element_size; if (hal.util->available_memory() < 100U + array_size) { // too risky to enable as we could run out of stack - return NULL; + return nullptr; } return calloc(1, array_size); @@ -59,7 +59,7 @@ bool AC_PolyFence_loader::save_point_to_eeprom(uint16_t i, const Vector2l& point bool AC_PolyFence_loader::boundary_valid(uint16_t num_points, const Vector2l* points, bool contains_return_point) const { // exit immediate if no points - if (points == NULL) { + if (points == nullptr) { return false; } @@ -87,7 +87,7 @@ bool AC_PolyFence_loader::boundary_valid(uint16_t num_points, const Vector2l* po bool AC_PolyFence_loader::boundary_valid(uint16_t num_points, const Vector2f* points, bool contains_return_point) const { // exit immediate if no points - if (points == NULL) { + if (points == nullptr) { return false; } @@ -118,7 +118,7 @@ bool AC_PolyFence_loader::boundary_valid(uint16_t num_points, const Vector2f* po bool AC_PolyFence_loader::boundary_breached(const Vector2l& location, uint16_t num_points, const Vector2l* points, bool contains_return_point) const { // exit immediate if no points - if (points == NULL) { + if (points == nullptr) { return false; } @@ -132,7 +132,7 @@ bool AC_PolyFence_loader::boundary_breached(const Vector2l& location, uint16_t n bool AC_PolyFence_loader::boundary_breached(const Vector2f& location, uint16_t num_points, const Vector2f* points, bool contains_return_point) const { // exit immediate if no points - if (points == NULL) { + if (points == nullptr) { return false; } diff --git a/libraries/AC_Fence/AC_PolyFence_loader.h b/libraries/AC_Fence/AC_PolyFence_loader.h index 5677f5822f..dd905a3e12 100644 --- a/libraries/AC_Fence/AC_PolyFence_loader.h +++ b/libraries/AC_Fence/AC_PolyFence_loader.h @@ -12,7 +12,7 @@ public: uint8_t max_points() const; // create buffer to hold copy of eeprom points in RAM - // returns NULL if not enough memory can be allocated + // returns nullptr if not enough memory can be allocated void* create_point_array(uint8_t element_size); // load boundary point from eeprom, returns true on successful load diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 35bbe0d39d..f9e67b6094 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -60,7 +60,7 @@ AC_PrecLand::AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav) : _inav(inav), _last_update_ms(0), _last_backend_los_meas_ms(0), - _backend(NULL) + _backend(nullptr) { // set parameters to defaults AP_Param::setup_object_defaults(this, var_info); @@ -74,12 +74,12 @@ AC_PrecLand::AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav) : void AC_PrecLand::init() { // exit immediately if init has already been run - if (_backend != NULL) { + if (_backend != nullptr) { return; } // default health to false - _backend = NULL; + _backend = nullptr; _backend_state.healthy = false; // instantiate backend based on type parameter @@ -101,7 +101,7 @@ void AC_PrecLand::init() } // init backend - if (_backend != NULL) { + if (_backend != nullptr) { _backend->init(); } } @@ -112,7 +112,7 @@ void AC_PrecLand::update(float rangefinder_alt_cm, bool rangefinder_alt_valid) _attitude_history.push_back(_ahrs.get_rotation_body_to_ned()); // run backend update - if (_backend != NULL && _enabled) { + if (_backend != nullptr && _enabled) { // read from sensor _backend->update(); @@ -228,7 +228,7 @@ bool AC_PrecLand::get_target_velocity_relative_cms(Vector2f& ret) const void AC_PrecLand::handle_msg(mavlink_message_t* msg) { // run backend update - if (_backend != NULL) { + if (_backend != nullptr) { _backend->handle_msg(msg); } } diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index f62d66d3b9..e7cb91d7b1 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -303,7 +303,7 @@ void AC_WPNav::calc_loiter_desired_velocity(float nav_dt, float ekfGndSpdLimit) } // Limit the velocity to prevent fence violations - if (_avoid != NULL) { + if (_avoid != nullptr) { _avoid->adjust_velocity(_pos_control.get_pos_xy_kP(), _loiter_accel_cmss, desired_vel); } @@ -1170,7 +1170,7 @@ bool AC_WPNav::get_terrain_offset(float& offset_cm) // use terrain database float terr_alt = 0.0f; - if (_terrain != NULL && _terrain->height_above_terrain(terr_alt, true)) { + if (_terrain != nullptr && _terrain->height_above_terrain(terr_alt, true)) { offset_cm = _inav.get_altitude() - (terr_alt * 100.0f); return true; } diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index 3059f0e185..25437b4004 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -313,8 +313,8 @@ protected: const AP_AHRS& _ahrs; AC_PosControl& _pos_control; const AC_AttitudeControl& _attitude_control; - AP_Terrain *_terrain = NULL; - AC_Avoid *_avoid = NULL; + AP_Terrain *_terrain = nullptr; + AC_Avoid *_avoid = nullptr; // parameters AP_Float _loiter_speed_cms; // maximum horizontal speed in cm/s while in loiter diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index d4301d9eea..fd8a079871 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -54,9 +54,9 @@ public: pitch_sensor(0), yaw_sensor(0), _vehicle_class(AHRS_VEHICLE_UNKNOWN), - _compass(NULL), - _optflow(NULL), - _airspeed(NULL), + _compass(nullptr), + _optflow(nullptr), + _airspeed(nullptr), _compass_last_update(0), _ins(ins), _baro(baro), @@ -140,7 +140,7 @@ public: // this makes initial config easier void set_orientation() { _ins.set_board_orientation((enum Rotation)_board_orientation.get()); - if (_compass != NULL) { + if (_compass != nullptr) { _compass->set_board_orientation((enum Rotation)_board_orientation.get()); } } @@ -278,7 +278,7 @@ public: // return true if airspeed comes from an airspeed sensor, as // opposed to an IMU estimate bool airspeed_sensor_enabled(void) const { - return _airspeed != NULL && _airspeed->use() && _airspeed->healthy(); + return _airspeed != nullptr && _airspeed->use() && _airspeed->healthy(); } // return a ground vector estimate in meters/second, in North/East order diff --git a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp index d347e7d15a..8b9292ef61 100644 --- a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp +++ b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp @@ -40,7 +40,7 @@ void setup(void) } else { hal.console->printf("No compass detected\n"); } - gps.init(NULL, serial_manager); + gps.init(nullptr, serial_manager); } void loop(void) diff --git a/libraries/AP_AccelCal/AP_AccelCal.cpp b/libraries/AP_AccelCal/AP_AccelCal.cpp index 88bf6b6784..254fedd284 100644 --- a/libraries/AP_AccelCal/AP_AccelCal.cpp +++ b/libraries/AP_AccelCal/AP_AccelCal.cpp @@ -45,7 +45,7 @@ void AP_AccelCal::update() } if(_start_collect_sample) { collect_sample(); - _gcs->set_snoop(NULL); + _gcs->set_snoop(nullptr); _start_collect_sample = false; } switch(_status) { @@ -55,7 +55,7 @@ void AP_AccelCal::update() case ACCEL_CAL_WAITING_FOR_ORIENTATION: { // if we're waiting for orientation, first ensure that all calibrators are on the same step uint8_t step; - if ((cal = get_calibrator(0)) == NULL) { + if ((cal = get_calibrator(0)) == nullptr) { fail(); return; } @@ -153,7 +153,7 @@ void AP_AccelCal::update() void AP_AccelCal::start(GCS_MAVLINK *gcs) { - if (gcs == NULL || _started) { + if (gcs == nullptr || _started) { return; } _start_collect_sample = false; @@ -218,7 +218,7 @@ void AP_AccelCal::clear() cal->clear(); } - _gcs = NULL; + _gcs = nullptr; _step = 0; _started = false; @@ -245,12 +245,12 @@ void AP_AccelCal::collect_sample() cal->collect_sample(); } // setup snooping of packets so we can see the COMMAND_ACK - _gcs->set_snoop(NULL); + _gcs->set_snoop(nullptr); update_status(); } void AP_AccelCal::register_client(AP_AccelCal_Client* client) { - if (client == NULL || _num_clients >= AP_ACCELCAL_MAX_NUM_CLIENTS) { + if (client == nullptr || _num_clients >= AP_ACCELCAL_MAX_NUM_CLIENTS) { return; } @@ -274,7 +274,7 @@ AccelCalibrator* AP_AccelCal::get_calibrator(uint8_t index) { index--; } } - return NULL; + return nullptr; } void AP_AccelCal::update_status() { diff --git a/libraries/AP_AccelCal/AccelCalibrator.cpp b/libraries/AP_AccelCal/AccelCalibrator.cpp index 5712da567a..d54df193f3 100644 --- a/libraries/AP_AccelCal/AccelCalibrator.cpp +++ b/libraries/AP_AccelCal/AccelCalibrator.cpp @@ -29,7 +29,7 @@ const extern AP_HAL::HAL& hal; AccelCalibrator::AccelCalibrator() : _conf_tolerance(ACCEL_CAL_TOLERANCE), -_sample_buffer(NULL) +_sample_buffer(nullptr) { clear(); } @@ -239,7 +239,7 @@ void AccelCalibrator::get_calibration(Vector3f& offset, Vector3f& diag, Vector3f */ bool AccelCalibrator::accept_sample(const Vector3f& sample) { - if (_sample_buffer == NULL) { + if (_sample_buffer == nullptr) { return false; } @@ -262,9 +262,9 @@ void AccelCalibrator::set_status(enum accel_cal_status_t status) { _status = ACCEL_CAL_NOT_STARTED; _samples_collected = 0; - if (_sample_buffer != NULL) { + if (_sample_buffer != nullptr) { free(_sample_buffer); - _sample_buffer = NULL; + _sample_buffer = nullptr; } break; @@ -273,9 +273,9 @@ void AccelCalibrator::set_status(enum accel_cal_status_t status) { //Callibrator has been started and is waiting for user to ack after orientation setting if (!running()) { _samples_collected = 0; - if (_sample_buffer == NULL) { + if (_sample_buffer == nullptr) { _sample_buffer = (struct AccelSample*)calloc(_conf_num_samples,sizeof(struct AccelSample)); - if (_sample_buffer == NULL) { + if (_sample_buffer == nullptr) { set_status(ACCEL_CAL_FAILED); break; } @@ -325,7 +325,7 @@ void AccelCalibrator::set_status(enum accel_cal_status_t status) { */ void AccelCalibrator::run_fit(uint8_t max_iterations, float& fitness) { - if (_sample_buffer == NULL) { + if (_sample_buffer == nullptr) { return; } fitness = calc_mean_squared_residuals(_param.s); @@ -407,7 +407,7 @@ float AccelCalibrator::calc_mean_squared_residuals() const // supplied float AccelCalibrator::calc_mean_squared_residuals(const struct param_t& params) const { - if (_sample_buffer == NULL || _samples_collected == 0) { + if (_sample_buffer == nullptr || _samples_collected == 0) { return 1.0e30f; } float sum = 0.0f; diff --git a/libraries/AP_Airspeed/AP_Airspeed_analog.cpp b/libraries/AP_Airspeed/AP_Airspeed_analog.cpp index 6e723a3027..86fede603d 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_analog.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_analog.cpp @@ -37,7 +37,7 @@ bool AP_Airspeed_Analog::init() // read the airspeed sensor bool AP_Airspeed_Analog::get_differential_pressure(float &pressure) { - if (_source == NULL) { + if (_source == nullptr) { return false; } _source->set_pin(_pin); diff --git a/libraries/AP_Airspeed/AP_Airspeed_analog.h b/libraries/AP_Airspeed/AP_Airspeed_analog.h index b2db84fab8..582ec39482 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_analog.h +++ b/libraries/AP_Airspeed/AP_Airspeed_analog.h @@ -9,7 +9,7 @@ class AP_Airspeed_Analog : public AP_Airspeed_Backend { public: AP_Airspeed_Analog(const AP_Int8 &pin, const AP_Float &psi_range) - : _source(NULL) + : _source(nullptr) , _pin(pin) , _psi_range(psi_range) { } diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 8d551ea120..0a3b0569a8 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -125,7 +125,7 @@ bool AP_Arming::airspeed_checks(bool report) if ((checks_to_perform & ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_AIRSPEED)) { const AP_Airspeed *airspeed = ahrs.get_airspeed(); - if (airspeed == NULL) { + if (airspeed == nullptr) { // not an airspeed capable vehicle return true; } diff --git a/libraries/AP_Avoidance/AP_Avoidance.cpp b/libraries/AP_Avoidance/AP_Avoidance.cpp index b19e9fac2a..d298ef1eb2 100644 --- a/libraries/AP_Avoidance/AP_Avoidance.cpp +++ b/libraries/AP_Avoidance/AP_Avoidance.cpp @@ -125,10 +125,10 @@ AP_Avoidance::AP_Avoidance(AP_AHRS &ahrs, AP_ADSB &adsb) : void AP_Avoidance::init(void) { debug("ADSB initialisation: %d obstacles", _obstacles_max.get()); - if (_obstacles == NULL) { + if (_obstacles == nullptr) { _obstacles = new AP_Avoidance::Obstacle[_obstacles_max]; - if (_obstacles == NULL) { + if (_obstacles == nullptr) { // dynamic RAM allocation of _obstacles[] failed, disable gracefully hal.console->printf("Unable to initialize Avoidance obstacle list\n"); // disable ourselves to avoid repeated allocation attempts diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index dd8fc12626..7b5c149d73 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -324,7 +324,7 @@ void AP_Baro::init(void) _num_drivers = 1; #endif - if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == NULL) { + if (_num_drivers == 0 || _num_sensors == 0 || drivers[0] == nullptr) { AP_HAL::panic("Baro: unable to initialise driver"); } } diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index eaa375e36c..281071a2ef 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -190,7 +190,7 @@ AP_BattMonitor::init() } // call init function for each backend - if (drivers[instance] != NULL) { + if (drivers[instance] != nullptr) { drivers[instance]->init(); } } @@ -201,7 +201,7 @@ void AP_BattMonitor::read() { for (uint8_t i=0; i<_num_instances; i++) { - if (drivers[i] != NULL && _monitoring[i] != BattMonitor_TYPE_NONE) { + if (drivers[i] != nullptr && _monitoring[i] != BattMonitor_TYPE_NONE) { drivers[i]->read(); } } @@ -220,7 +220,7 @@ bool AP_BattMonitor::is_powering_off(uint8_t instance) const { bool AP_BattMonitor::has_current(uint8_t instance) const { // check for analog voltage and current monitor or smbus monitor - if (instance < _num_instances && drivers[instance] != NULL) { + if (instance < _num_instances && drivers[instance] != nullptr) { return (_monitoring[instance] == BattMonitor_TYPE_ANALOG_VOLTAGE_AND_CURRENT || _monitoring[instance] == BattMonitor_TYPE_SMBUS || _monitoring[instance] == BattMonitor_TYPE_BEBOP); @@ -261,7 +261,7 @@ float AP_BattMonitor::current_total_mah(uint8_t instance) const { /// capacity_remaining_pct - returns the % battery capacity remaining (0 ~ 100) uint8_t AP_BattMonitor::capacity_remaining_pct(uint8_t instance) const { - if (instance < _num_instances && drivers[instance] != NULL) { + if (instance < _num_instances && drivers[instance] != nullptr) { return drivers[instance]->capacity_remaining_pct(); } else { return 0; diff --git a/libraries/AP_BoardConfig/px4_drivers.cpp b/libraries/AP_BoardConfig/px4_drivers.cpp index 3a8aa70884..80d0494afe 100644 --- a/libraries/AP_BoardConfig/px4_drivers.cpp +++ b/libraries/AP_BoardConfig/px4_drivers.cpp @@ -122,7 +122,7 @@ void AP_BoardConfig::px4_setup_uart() { #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 hal.uartC->set_flow_control((AP_HAL::UARTDriver::flow_control)px4.ser1_rtscts.get()); - if (hal.uartD != NULL) { + if (hal.uartD != nullptr) { hal.uartD->set_flow_control((AP_HAL::UARTDriver::flow_control)px4.ser2_rtscts.get()); } #endif diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index 6ae3f758a3..0190035495 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -10,8 +10,8 @@ extern const AP_HAL::HAL& hal; -const AP_AHRS_NavEKF *Location_Class::_ahrs = NULL; -AP_Terrain *Location_Class::_terrain = NULL; +const AP_AHRS_NavEKF *Location_Class::_ahrs = nullptr; +AP_Terrain *Location_Class::_terrain = nullptr; // scalers to convert latitude and longitude to meters. Duplicated from location.cpp #define LOCATION_SCALING_FACTOR 0.011131884502145034f @@ -45,7 +45,7 @@ Location_Class::Location_Class(const Vector3f &ekf_offset_neu) set_alt_cm(ekf_offset_neu.z, ALT_FRAME_ABOVE_ORIGIN); // calculate lat, lon - if (_ahrs != NULL) { + if (_ahrs != nullptr) { Location ekf_origin; if (_ahrs->get_origin(ekf_origin)) { lat = ekf_origin.lat; @@ -130,7 +130,7 @@ bool Location_Class::get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) co float alt_terr_cm = 0; if (frame == ALT_FRAME_ABOVE_TERRAIN || desired_frame == ALT_FRAME_ABOVE_TERRAIN) { #if AP_TERRAIN_AVAILABLE - if (_ahrs == NULL || _terrain == NULL || !_terrain->height_amsl(*(Location *)this, alt_terr_cm, true)) { + if (_ahrs == nullptr || _terrain == nullptr || !_terrain->height_amsl(*(Location *)this, alt_terr_cm, true)) { return false; } // convert terrain alt to cm @@ -153,7 +153,7 @@ bool Location_Class::get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) co { // fail if we cannot get ekf origin Location ekf_origin; - if (_ahrs == NULL || !_ahrs->get_origin(ekf_origin)) { + if (_ahrs == nullptr || !_ahrs->get_origin(ekf_origin)) { return false; } alt_abs = alt + ekf_origin.alt; @@ -179,7 +179,7 @@ bool Location_Class::get_alt_cm(ALT_FRAME desired_frame, int32_t &ret_alt_cm) co { // fail if we cannot get ekf origin Location ekf_origin; - if (_ahrs == NULL || !_ahrs->get_origin(ekf_origin)) { + if (_ahrs == nullptr || !_ahrs->get_origin(ekf_origin)) { return false; } ret_alt_cm = alt_abs - ekf_origin.alt; diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 33ce804cf4..be82d46372 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -420,7 +420,7 @@ Compass::Compass(void) : { AP_Param::setup_object_defaults(this, var_info); for (uint8_t i=0; iinit()) { delete sensor; - return NULL; + return nullptr; } return sensor; } diff --git a/libraries/AP_Compass/AP_Compass_PX4.cpp b/libraries/AP_Compass/AP_Compass_PX4.cpp index 1561c8dc70..33ad9e82cf 100644 --- a/libraries/AP_Compass/AP_Compass_PX4.cpp +++ b/libraries/AP_Compass/AP_Compass_PX4.cpp @@ -51,12 +51,12 @@ AP_Compass_PX4::AP_Compass_PX4(Compass &compass): AP_Compass_Backend *AP_Compass_PX4::detect(Compass &compass) { AP_Compass_PX4 *sensor = new AP_Compass_PX4(compass); - if (sensor == NULL) { - return NULL; + if (sensor == nullptr) { + return nullptr; } if (!sensor->init()) { delete sensor; - return NULL; + return nullptr; } return sensor; } diff --git a/libraries/AP_Compass/AP_Compass_QURT.cpp b/libraries/AP_Compass/AP_Compass_QURT.cpp index 79d4054eec..e819fe3f5c 100644 --- a/libraries/AP_Compass/AP_Compass_QURT.cpp +++ b/libraries/AP_Compass/AP_Compass_QURT.cpp @@ -34,12 +34,12 @@ AP_Compass_QURT::AP_Compass_QURT(Compass &compass): AP_Compass_Backend *AP_Compass_QURT::detect(Compass &compass) { AP_Compass_QURT *sensor = new AP_Compass_QURT(compass); - if (sensor == NULL) { - return NULL; + if (sensor == nullptr) { + return nullptr; } if (!sensor->init()) { delete sensor; - return NULL; + return nullptr; } return sensor; } diff --git a/libraries/AP_Compass/AP_Compass_qflight.cpp b/libraries/AP_Compass/AP_Compass_qflight.cpp index 8d91c60a42..20b02772a9 100644 --- a/libraries/AP_Compass/AP_Compass_qflight.cpp +++ b/libraries/AP_Compass/AP_Compass_qflight.cpp @@ -34,12 +34,12 @@ AP_Compass_QFLIGHT::AP_Compass_QFLIGHT(Compass &compass): AP_Compass_Backend *AP_Compass_QFLIGHT::detect(Compass &compass) { AP_Compass_QFLIGHT *sensor = new AP_Compass_QFLIGHT(compass); - if (sensor == NULL) { - return NULL; + if (sensor == nullptr) { + return nullptr; } if (!sensor->init()) { delete sensor; - return NULL; + return nullptr; } return sensor; } diff --git a/libraries/AP_Compass/CompassCalibrator.cpp b/libraries/AP_Compass/CompassCalibrator.cpp index f83493de37..38457ff6ff 100644 --- a/libraries/AP_Compass/CompassCalibrator.cpp +++ b/libraries/AP_Compass/CompassCalibrator.cpp @@ -77,7 +77,7 @@ extern const AP_HAL::HAL& hal; CompassCalibrator::CompassCalibrator(): _tolerance(COMPASS_CAL_DEFAULT_TOLERANCE), -_sample_buffer(NULL) +_sample_buffer(nullptr) { clear(); } @@ -263,9 +263,9 @@ bool CompassCalibrator::set_status(compass_cal_status_t status) { reset_state(); _status = COMPASS_CAL_NOT_STARTED; - if(_sample_buffer != NULL) { + if(_sample_buffer != nullptr) { free(_sample_buffer); - _sample_buffer = NULL; + _sample_buffer = nullptr; } return true; @@ -285,13 +285,13 @@ bool CompassCalibrator::set_status(compass_cal_status_t status) { return false; } - if (_sample_buffer == NULL) { + if (_sample_buffer == nullptr) { _sample_buffer = (CompassSample*) malloc(sizeof(CompassSample) * COMPASS_CAL_NUM_SAMPLES); } - if(_sample_buffer != NULL) { + if(_sample_buffer != nullptr) { initialize_fit(); _status = COMPASS_CAL_RUNNING_STEP_ONE; return true; @@ -313,9 +313,9 @@ bool CompassCalibrator::set_status(compass_cal_status_t status) { return false; } - if(_sample_buffer != NULL) { + if(_sample_buffer != nullptr) { free(_sample_buffer); - _sample_buffer = NULL; + _sample_buffer = nullptr; } _status = COMPASS_CAL_SUCCESS; @@ -331,9 +331,9 @@ bool CompassCalibrator::set_status(compass_cal_status_t status) { return true; } - if(_sample_buffer != NULL) { + if(_sample_buffer != nullptr) { free(_sample_buffer); - _sample_buffer = NULL; + _sample_buffer = nullptr; } _status = COMPASS_CAL_FAILED; @@ -363,7 +363,7 @@ bool CompassCalibrator::fit_acceptable() { } void CompassCalibrator::thin_samples() { - if(_sample_buffer == NULL) { + if(_sample_buffer == nullptr) { return; } @@ -410,7 +410,7 @@ bool CompassCalibrator::accept_sample(const Vector3f& sample) static const float a = (4.0f * M_PI / (3.0f * faces)) + M_PI / 3.0f; static const float theta = 0.5f * acosf(cosf(a) / (1.0f - cosf(a))); - if(_sample_buffer == NULL) { + if(_sample_buffer == nullptr) { return false; } @@ -445,7 +445,7 @@ float CompassCalibrator::calc_mean_squared_residuals() const float CompassCalibrator::calc_mean_squared_residuals(const param_t& params) const { - if(_sample_buffer == NULL || _samples_collected == 0) { + if(_sample_buffer == nullptr || _samples_collected == 0) { return 1.0e30f; } float sum = 0.0f; @@ -493,7 +493,7 @@ void CompassCalibrator::calc_initial_offset() void CompassCalibrator::run_sphere_fit() { - if(_sample_buffer == NULL) { + if(_sample_buffer == nullptr) { return; } @@ -607,7 +607,7 @@ void CompassCalibrator::calc_ellipsoid_jacob(const Vector3f& sample, const param void CompassCalibrator::run_ellipsoid_fit() { - if(_sample_buffer == NULL) { + if(_sample_buffer == nullptr) { return; } diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp index 3407cd772b..9657d64018 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp @@ -57,7 +57,7 @@ void AP_Frsky_Telem::init(const AP_SerialManager &serial_manager, const char *fi } } - if (_port != NULL) { + if (_port != nullptr) { hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_Frsky_Telem::tick, void)); // we don't want flow control for either protocol _port->set_flow_control(AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE); diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index e307f48d9c..014421c611 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -235,7 +235,7 @@ void AP_GPS::send_blob_start(uint8_t instance, const char *_blob, uint16_t size) void AP_GPS::send_blob_update(uint8_t instance) { // exit immediately if no uart for this instance - if (_port[instance] == NULL) { + if (_port[instance] == nullptr) { return; } @@ -262,7 +262,7 @@ void AP_GPS::send_blob_update(uint8_t instance) void AP_GPS::detect_instance(uint8_t instance) { - AP_GPS_Backend *new_gps = NULL; + AP_GPS_Backend *new_gps = nullptr; struct detect_state *dstate = &detect_state[instance]; uint32_t now = AP_HAL::millis(); @@ -288,11 +288,11 @@ AP_GPS::detect_instance(uint8_t instance) // do not try to detect the MAV type, assume it's there if (_type[instance] == GPS_TYPE_MAV) { _broadcast_gps_type("MAV", instance, -1); - new_gps = new AP_GPS_MAV(*this, state[instance], NULL); + new_gps = new AP_GPS_MAV(*this, state[instance], nullptr); goto found_gps; } - if (_port[instance] == NULL) { + if (_port[instance] == nullptr) { // UART not available return; } @@ -342,7 +342,7 @@ AP_GPS::detect_instance(uint8_t instance) } while (initblob_state[instance].remaining == 0 && _port[instance]->available() > 0 - && new_gps == NULL) { + && new_gps == nullptr) { uint8_t data = _port[instance]->read(); /* running a uBlox at less than 38400 will lead to packet @@ -395,7 +395,7 @@ AP_GPS::detect_instance(uint8_t instance) } found_gps: - if (new_gps != NULL) { + if (new_gps != nullptr) { state[instance].status = NO_FIX; drivers[instance] = new_gps; timing[instance].last_message_time_ms = now; @@ -405,7 +405,7 @@ found_gps: AP_GPS::GPS_Status AP_GPS::highest_supported_status(uint8_t instance) const { - if (drivers[instance] != NULL) + if (drivers[instance] != nullptr) return drivers[instance]->highest_supported_status(); return AP_GPS::GPS_OK_FIX_3D; } @@ -413,7 +413,7 @@ AP_GPS::highest_supported_status(uint8_t instance) const AP_GPS::GPS_Status AP_GPS::highest_supported_status(void) const { - if (drivers[primary_instance] != NULL) + if (drivers[primary_instance] != nullptr) return drivers[primary_instance]->highest_supported_status(); return AP_GPS::GPS_OK_FIX_3D; } @@ -440,7 +440,7 @@ AP_GPS::update_instance(uint8_t instance) return; } - if (drivers[instance] == NULL || state[instance].status == NO_GPS) { + if (drivers[instance] == nullptr || state[instance].status == NO_GPS) { // we don't yet know the GPS type of this one, or it has timed // out and needs to be re-initialised detect_instance(instance); @@ -463,7 +463,7 @@ AP_GPS::update_instance(uint8_t instance) // free the driver before we run the next detection, so we // don't end up with two allocated at any time delete drivers[instance]; - drivers[instance] = NULL; + drivers[instance] = nullptr; memset(&state[instance], 0, sizeof(state[instance])); state[instance].instance = instance; state[instance].status = NO_GPS; @@ -544,7 +544,7 @@ AP_GPS::handle_msg(const mavlink_message_t *msg) } uint8_t i; for (i=0; ihandle_msg(msg); } } @@ -634,7 +634,7 @@ AP_GPS::inject_data(uint8_t *data, uint8_t len) void AP_GPS::inject_data(uint8_t instance, uint8_t *data, uint8_t len) { - if (instance < GPS_MAX_INSTANCES && drivers[instance] != NULL) + if (instance < GPS_MAX_INSTANCES && drivers[instance] != nullptr) drivers[instance]->inject_data(data, len); } @@ -704,7 +704,7 @@ AP_GPS::send_mavlink_gps2_raw(mavlink_channel_t chan) void AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan) { - if (drivers[0] != NULL && drivers[0]->highest_supported_status() > AP_GPS::GPS_OK_FIX_3D) { + if (drivers[0] != nullptr && drivers[0]->highest_supported_status() > AP_GPS::GPS_OK_FIX_3D) { drivers[0]->send_mavlink_gps_rtk(chan); } } @@ -712,7 +712,7 @@ AP_GPS::send_mavlink_gps_rtk(mavlink_channel_t chan) void AP_GPS::send_mavlink_gps2_rtk(mavlink_channel_t chan) { - if (drivers[1] != NULL && drivers[1]->highest_supported_status() > AP_GPS::GPS_OK_FIX_3D) { + if (drivers[1] != nullptr && drivers[1]->highest_supported_status() > AP_GPS::GPS_OK_FIX_3D) { drivers[1]->send_mavlink_gps_rtk(chan); } } @@ -721,7 +721,7 @@ uint8_t AP_GPS::first_unconfigured_gps(void) const { for(int i = 0; i < GPS_MAX_INSTANCES; i++) { - if(_type[i] != GPS_TYPE_NONE && (drivers[i] == NULL || !drivers[i]->is_configured())) { + if(_type[i] != GPS_TYPE_NONE && (drivers[i] == nullptr || !drivers[i]->is_configured())) { return i; } } @@ -731,7 +731,7 @@ AP_GPS::first_unconfigured_gps(void) const void AP_GPS::broadcast_first_configuration_failure_reason(void) const { uint8_t unconfigured = first_unconfigured_gps(); - if (drivers[unconfigured] == NULL) { + if (drivers[unconfigured] == nullptr) { GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "GPS %d: was not found", unconfigured + 1); } else { drivers[unconfigured]->broadcast_configuration_failure_reason(); @@ -835,7 +835,7 @@ void AP_GPS::inject_data_all(const uint8_t *data, uint16_t len) { uint8_t i; for (i=0; iinject_data(data, len); } } diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index 0ec1a1159d..f8b4811cb9 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -118,11 +118,11 @@ bool AP_GPS_NMEA::read(void) while (numc--) { char c = port->read(); #ifdef NMEA_LOG_PATH - static FILE *logf = NULL; - if (logf == NULL) { + static FILE *logf = nullptr; + if (logf == nullptr) { logf = fopen(NMEA_LOG_PATH, "wb"); } - if (logf != NULL) { + if (logf != nullptr) { ::fwrite(&c, 1, 1, logf); } #endif diff --git a/libraries/AP_GPS/AP_GPS_SBF.cpp b/libraries/AP_GPS/AP_GPS_SBF.cpp index cbd2e631b1..4f5f2d2d0c 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.cpp +++ b/libraries/AP_GPS/AP_GPS_SBF.cpp @@ -163,7 +163,7 @@ AP_GPS_SBF::parse(uint8_t temp) void AP_GPS_SBF::log_ExtEventPVTGeodetic(const msg4007 &temp) { - if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) { + if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) { return; } diff --git a/libraries/AP_GPS/AP_GPS_SBP.cpp b/libraries/AP_GPS/AP_GPS_SBP.cpp index 702d6be148..100fd9d0db 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.cpp +++ b/libraries/AP_GPS/AP_GPS_SBP.cpp @@ -387,7 +387,7 @@ void AP_GPS_SBP::logging_log_full_update() { - if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) { + if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) { return; } @@ -408,7 +408,7 @@ AP_GPS_SBP::logging_log_raw_sbp(uint16_t msg_type, uint8_t msg_len, uint8_t *msg_buff) { - if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) { + if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) { return; } diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 8dacd5e874..86a9d88b85 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -68,7 +68,7 @@ AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UART noReceivedHdop(true) { // stop any config strings that are pending - gps.send_blob_start(state.instance, NULL, 0); + gps.send_blob_start(state.instance, nullptr, 0); // start the process of updating the GPS rates _request_next_config(); @@ -114,16 +114,16 @@ AP_GPS_UBLOX::_request_next_config(void) } break; case STEP_POLL_SBAS: - _send_message(CLASS_CFG, MSG_CFG_SBAS, NULL, 0); + _send_message(CLASS_CFG, MSG_CFG_SBAS, nullptr, 0); break; case STEP_POLL_NAV: - _send_message(CLASS_CFG, MSG_CFG_NAV_SETTINGS, NULL, 0); + _send_message(CLASS_CFG, MSG_CFG_NAV_SETTINGS, nullptr, 0); break; case STEP_POLL_GNSS: - _send_message(CLASS_CFG, MSG_CFG_GNSS, NULL, 0); + _send_message(CLASS_CFG, MSG_CFG_GNSS, nullptr, 0); break; case STEP_NAV_RATE: - _send_message(CLASS_CFG, MSG_CFG_RATE, NULL, 0); + _send_message(CLASS_CFG, MSG_CFG_RATE, nullptr, 0); break; case STEP_POSLLH: if(!_request_message_rate(CLASS_NAV, MSG_POSLLH)) { @@ -307,7 +307,7 @@ AP_GPS_UBLOX::_request_port(void) // not enough space - do it next time return; } - _send_message(CLASS_CFG, MSG_CFG_PRT, NULL, 0); + _send_message(CLASS_CFG, MSG_CFG_PRT, nullptr, 0); } // Ensure there is enough space for the largest possible outgoing message // Process bytes available from the stream @@ -462,7 +462,7 @@ AP_GPS_UBLOX::read(void) // Private Methods ///////////////////////////////////////////////////////////// void AP_GPS_UBLOX::log_mon_hw(void) { - if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) { + if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) { return; } struct log_Ubx1 pkt = { @@ -485,7 +485,7 @@ void AP_GPS_UBLOX::log_mon_hw(void) void AP_GPS_UBLOX::log_mon_hw2(void) { - if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) { + if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) { return; } @@ -504,7 +504,7 @@ void AP_GPS_UBLOX::log_mon_hw2(void) #if UBLOX_RXM_RAW_LOGGING void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw) { - if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) { + if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) { return; } uint64_t now = AP_HAL::micros64(); @@ -529,7 +529,7 @@ void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw) void AP_GPS_UBLOX::log_rxm_rawx(const struct ubx_rxm_rawx &raw) { - if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) { + if (gps._DataFlash == nullptr || !gps._DataFlash->logging_started()) { return; } uint64_t now = AP_HAL::micros64(); @@ -1138,7 +1138,7 @@ reset: void AP_GPS_UBLOX::_request_version(void) { - _send_message(CLASS_MON, MSG_MON_VER, NULL, 0); + _send_message(CLASS_MON, MSG_MON_VER, nullptr, 0); } void diff --git a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp index 40e1282f4c..1257dbc576 100644 --- a/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp +++ b/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp @@ -58,7 +58,7 @@ void setup() // Initialize the UART for GPS system serial_manager.init(); - gps.init(NULL, serial_manager); + gps.init(nullptr, serial_manager); } void loop() diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index 469864282c..0265d43184 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -152,7 +152,7 @@ #endif #ifndef HAL_PARAM_DEFAULTS_PATH -#define HAL_PARAM_DEFAULTS_PATH NULL +#define HAL_PARAM_DEFAULTS_PATH nullptr #endif #ifndef HAL_HAVE_IMU_HEATER diff --git a/libraries/AP_HAL/Util.cpp b/libraries/AP_HAL/Util.cpp index 2a44021a0b..ab51270b88 100644 --- a/libraries/AP_HAL/Util.cpp +++ b/libraries/AP_HAL/Util.cpp @@ -55,7 +55,7 @@ uint64_t AP_HAL::Util::get_system_clock_ms() const { #if defined(__APPLE__) && defined(__MACH__) struct timeval ts; - gettimeofday(&ts, NULL); + gettimeofday(&ts, nullptr); return ((long long)((ts.tv_sec * 1000) + (ts.tv_usec / 1000))); #else struct timespec ts; diff --git a/libraries/AP_HAL/Util.h b/libraries/AP_HAL/Util.h index 4e7549aa9b..22c61da1dd 100644 --- a/libraries/AP_HAL/Util.h +++ b/libraries/AP_HAL/Util.h @@ -18,8 +18,8 @@ public: void clear_capabilities(uint64_t cap) { capabilities &= ~(cap); } uint64_t get_capabilities() const { return capabilities; } - virtual const char* get_custom_log_directory() { return NULL; } - virtual const char* get_custom_terrain_directory() const { return NULL; } + virtual const char* get_custom_log_directory() { return nullptr; } + virtual const char* get_custom_terrain_directory() const { return nullptr; } // get path to custom defaults file for AP_Param virtual const char* get_custom_defaults_file() const { @@ -86,7 +86,7 @@ public: /* return a stream for access to a system shell, if available */ - virtual AP_HAL::Stream *get_shell_stream() { return NULL; } + virtual AP_HAL::Stream *get_shell_stream() { return nullptr; } /* Support for an imu heating system */ virtual void set_imu_temp(float current) {} @@ -103,7 +103,7 @@ public: PC_INTERVAL /**< measure the interval between instances of an event */ }; typedef void *perf_counter_t; - virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name) { return NULL; } + virtual perf_counter_t perf_alloc(perf_counter_type t, const char *name) { return nullptr; } virtual void perf_begin(perf_counter_t h) {} virtual void perf_end(perf_counter_t h) {} virtual void perf_count(perf_counter_t h) {} diff --git a/libraries/AP_HAL/examples/UART_test/UART_test.cpp b/libraries/AP_HAL/examples/UART_test/UART_test.cpp index 42643b6fbd..3afbc31016 100644 --- a/libraries/AP_HAL/examples/UART_test/UART_test.cpp +++ b/libraries/AP_HAL/examples/UART_test/UART_test.cpp @@ -15,7 +15,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); */ static void setup_uart(AP_HAL::UARTDriver *uart, const char *name) { - if (uart == NULL) { + if (uart == nullptr) { // that UART doesn't exist on this platform return; } @@ -37,7 +37,7 @@ void setup(void) static void test_uart(AP_HAL::UARTDriver *uart, const char *name) { - if (uart == NULL) { + if (uart == nullptr) { // that UART doesn't exist on this platform return; } diff --git a/libraries/AP_HAL/utility/RingBuffer.h b/libraries/AP_HAL/utility/RingBuffer.h index 8d0ad2e794..b5b57b9d54 100644 --- a/libraries/AP_HAL/utility/RingBuffer.h +++ b/libraries/AP_HAL/utility/RingBuffer.h @@ -278,7 +278,7 @@ public: } // allow array indexing, based on current head. Returns a pointer - // to the object or NULL + // to the object or nullptr T * operator[](uint16_t i) { if (i >= count) { return nullptr; diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index 40ba0b08b5..09b2ffc739 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -169,7 +169,7 @@ bool SocketAPM::pollin(uint32_t timeout_ms) tv.tv_sec = timeout_ms / 1000; tv.tv_usec = (timeout_ms % 1000) * 1000UL; - if (select(fd+1, &fds, NULL, NULL, &tv) != 1) { + if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) { return false; } return true; @@ -190,7 +190,7 @@ bool SocketAPM::pollout(uint32_t timeout_ms) tv.tv_sec = timeout_ms / 1000; tv.tv_usec = (timeout_ms % 1000) * 1000UL; - if (select(fd+1, NULL, &fds, NULL, &tv) != 1) { + if (select(fd+1, nullptr, &fds, nullptr, &tv) != 1) { return false; } return true; @@ -211,12 +211,12 @@ bool SocketAPM::listen(uint16_t backlog) SocketAPM *SocketAPM::accept(uint32_t timeout_ms) { if (!pollin(timeout_ms)) { - return NULL; + return nullptr; } - int newfd = ::accept(fd, NULL, NULL); + int newfd = ::accept(fd, nullptr, nullptr); if (newfd == -1) { - return NULL; + return nullptr; } // turn off nagle for lower latency int one = 1; diff --git a/libraries/AP_HAL/utility/dsm.cpp b/libraries/AP_HAL/utility/dsm.cpp index c683287738..42d2b3817d 100644 --- a/libraries/AP_HAL/utility/dsm.cpp +++ b/libraries/AP_HAL/utility/dsm.cpp @@ -506,7 +506,7 @@ int main(int argc, const char *argv[]) tv.tv_usec = 0; // check if any bytes are available - if (select(fd+1, &fds, NULL, NULL, &tv) != 1) { + if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) { break; } diff --git a/libraries/AP_HAL/utility/getopt_cpp.cpp b/libraries/AP_HAL/utility/getopt_cpp.cpp index 9a7f3a4099..114bfcacef 100644 --- a/libraries/AP_HAL/utility/getopt_cpp.cpp +++ b/libraries/AP_HAL/utility/getopt_cpp.cpp @@ -57,7 +57,7 @@ GetOptLong::GetOptLong(int _argc, char *const _argv[], const char *_optstring, c optind(1), optopt(0), longindex(-1), - optarg(NULL), + optarg(nullptr), argc(_argc), argv(_argv), optstring(_optstring), @@ -106,7 +106,7 @@ int GetOptLong::getoption(void) place++; namelen = strcspn(place, "="); - for (i = 0; longopts[i].name != NULL; i++) + for (i = 0; longopts[i].name != nullptr; i++) { if (strlen(longopts[i].name) == namelen && strncmp(place, longopts[i].name, namelen) == 0) @@ -135,7 +135,7 @@ int GetOptLong::getoption(void) } else { - optarg = NULL; + optarg = nullptr; if (place[namelen] != 0) { /* XXX error? */ @@ -148,7 +148,7 @@ int GetOptLong::getoption(void) place = ""; - if (longopts[i].flag == NULL) + if (longopts[i].flag == nullptr) return longopts[i].val; else { @@ -183,7 +183,7 @@ int GetOptLong::getoption(void) if (oli[1] != ':') { /* don't need argument */ - optarg = NULL; + optarg = nullptr; if (!*place) ++optind; } diff --git a/libraries/AP_HAL/utility/srxl.cpp b/libraries/AP_HAL/utility/srxl.cpp index 054f46f02b..89ed52e725 100644 --- a/libraries/AP_HAL/utility/srxl.cpp +++ b/libraries/AP_HAL/utility/srxl.cpp @@ -218,7 +218,7 @@ int main(int argc, const char *argv[]) tv.tv_usec = 0; // check if any bytes are available - if (select(fd+1, &fds, NULL, NULL, &tv) != 1) { + if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) { break; } diff --git a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp index 8cecf8ffcb..dc5e31c021 100644 --- a/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp +++ b/libraries/AP_HAL_Empty/HAL_Empty_Class.cpp @@ -27,9 +27,9 @@ HAL_Empty::HAL_Empty() : &uartADriver, &uartBDriver, &uartCDriver, - NULL, /* no uartD */ - NULL, /* no uartE */ - NULL, /* no uartF */ + nullptr, /* no uartD */ + nullptr, /* no uartE */ + nullptr, /* no uartF */ &spiDeviceManager, &analogIn, &storageDriver, diff --git a/libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp b/libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp index aeb0959909..5c5b6339b0 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp +++ b/libraries/AP_HAL_Linux/AnalogIn_ADS1115.cpp @@ -50,14 +50,14 @@ AnalogIn_ADS1115::AnalogIn_ADS1115() AP_HAL::AnalogSource* AnalogIn_ADS1115::channel(int16_t pin) { for (uint8_t j = 0; j < _channels_number; j++) { - if (_channels[j] == NULL) { + if (_channels[j] == nullptr) { _channels[j] = new AnalogSource_ADS1115(pin); return _channels[j]; } } hal.console->println("Out of analog channels"); - return NULL; + return nullptr; } void AnalogIn_ADS1115::init() @@ -83,7 +83,7 @@ void AnalogIn_ADS1115::_update() for (uint8_t j=0; j < rc; j++) { AnalogSource_ADS1115 *source = _channels[j]; - if (source != NULL && reports[i].id == source->_pin) { + if (source != nullptr && reports[i].id == source->_pin) { source->_value = reports[i].data / 1000; } } diff --git a/libraries/AP_HAL_Linux/AnalogIn_Raspilot.cpp b/libraries/AP_HAL_Linux/AnalogIn_Raspilot.cpp index c32773d9ff..29e349c801 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_Raspilot.cpp +++ b/libraries/AP_HAL_Linux/AnalogIn_Raspilot.cpp @@ -61,14 +61,14 @@ float AnalogIn_Raspilot::board_voltage(void) AP_HAL::AnalogSource* AnalogIn_Raspilot::channel(int16_t pin) { for (uint8_t j = 0; j < _channels_number; j++) { - if (_channels[j] == NULL) { + if (_channels[j] == nullptr) { _channels[j] = new AnalogSource_Raspilot(pin); return _channels[j]; } } hal.console->println("Out of analog channels"); - return NULL; + return nullptr; } void AnalogIn_Raspilot::init() @@ -125,7 +125,7 @@ void AnalogIn_Raspilot::_update() for (int16_t j=0; j < RASPILOT_ADC_MAX_CHANNELS; j++) { AnalogSource_Raspilot *source = _channels[j]; - if (source != NULL && i == source->_pin) { + if (source != nullptr && i == source->_pin) { source->_value = rx.regs[i] * 3.3 / 4096.0; } } diff --git a/libraries/AP_HAL_Linux/CameraSensor_Mt9v117.cpp b/libraries/AP_HAL_Linux/CameraSensor_Mt9v117.cpp index a36c432e83..32fe9ed363 100644 --- a/libraries/AP_HAL_Linux/CameraSensor_Mt9v117.cpp +++ b/libraries/AP_HAL_Linux/CameraSensor_Mt9v117.cpp @@ -197,7 +197,7 @@ void CameraSensor_Mt9v117::_write_reg32(uint16_t reg, uint32_t val) buf[4] = (uint8_t) ((val >> 8) & 0xFF); buf[5] = (uint8_t) (val & 0xFF); - if (!_dev->transfer(buf, 6, NULL, 0)) { + if (!_dev->transfer(buf, 6, nullptr, 0)) { hal.console->printf("mt9v117: error writing 0x%8x\n", reg); } } diff --git a/libraries/AP_HAL_Linux/GPIO_RPI.cpp b/libraries/AP_HAL_Linux/GPIO_RPI.cpp index 56834913aa..3e6cea1901 100644 --- a/libraries/AP_HAL_Linux/GPIO_RPI.cpp +++ b/libraries/AP_HAL_Linux/GPIO_RPI.cpp @@ -55,7 +55,7 @@ void GPIO_RPI::init() // mmap GPIO void *gpio_map = mmap( - NULL, // Any adddress in our space will do + nullptr, // Any adddress in our space will do BLOCK_SIZE, // Map length PROT_READ|PROT_WRITE, // Enable reading & writting to mapped memory MAP_SHARED, // Shared with other processes diff --git a/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp b/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp index 5de459aa01..a069a240d1 100644 --- a/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp +++ b/libraries/AP_HAL_Linux/OpticalFlow_Onboard.cpp @@ -68,7 +68,7 @@ void OpticalFlow_Onboard::init(AP_HAL::OpticalFlow::Gyro_Cb get_gyro) left = (HAL_OPTFLOW_ONBOARD_SENSOR_WIDTH - HAL_OPTFLOW_ONBOARD_SENSOR_HEIGHT) / 2; - if (device_path == NULL || + if (device_path == nullptr || !_videoin->open_device(device_path, memtype)) { AP_HAL::panic("OpticalFlow_Onboard: couldn't open " "video device"); @@ -170,7 +170,7 @@ void OpticalFlow_Onboard::init(AP_HAL::OpticalFlow::Gyro_Cb get_gyro) /* Create the thread that will be waiting for frames * Initialize thread and mutex */ - ret = pthread_mutex_init(&_mutex, NULL); + ret = pthread_mutex_init(&_mutex, nullptr); if (ret != 0) { AP_HAL::panic("OpticalFlow_Onboard: failed to init mutex"); } @@ -222,7 +222,7 @@ void *OpticalFlow_Onboard::_read_thread(void *arg) OpticalFlow_Onboard *optflow_onboard = (OpticalFlow_Onboard *) arg; optflow_onboard->_run_optflow(); - return NULL; + return nullptr; } void OpticalFlow_Onboard::_run_optflow() @@ -235,7 +235,7 @@ void OpticalFlow_Onboard::_run_optflow() uint32_t crop_left = 0, crop_top = 0; uint32_t shrink_scale = 0, shrink_width = 0, shrink_height = 0; uint32_t shrink_width_offset = 0, shrink_height_offset = 0; - uint8_t *convert_buffer = NULL, *output_buffer = NULL; + uint8_t *convert_buffer = nullptr, *output_buffer = nullptr; uint8_t qual; if (_format == V4L2_PIX_FMT_YUYV) { @@ -330,7 +330,7 @@ void OpticalFlow_Onboard::_run_optflow() /* if it is at least the second frame we receive * since we have to compare 2 frames */ - if (_last_video_frame.data == NULL) { + if (_last_video_frame.data == nullptr) { _last_video_frame = video_frame; continue; } diff --git a/libraries/AP_HAL_Linux/PWM_Sysfs.cpp b/libraries/AP_HAL_Linux/PWM_Sysfs.cpp index 4e87be4eb4..20ad6e404a 100644 --- a/libraries/AP_HAL_Linux/PWM_Sysfs.cpp +++ b/libraries/AP_HAL_Linux/PWM_Sysfs.cpp @@ -39,8 +39,8 @@ PWM_Sysfs_Base::PWM_Sysfs_Base(char* export_path, char* polarity_path, , _duty_path(duty_path) , _period_path(period_path) { - if (_export_path == NULL || _enable_path == NULL || - _period_path == NULL || _duty_path == NULL) { + if (_export_path == nullptr || _enable_path == nullptr || + _period_path == nullptr || _duty_path == nullptr) { AP_HAL::panic("PWM_Sysfs: export=%p enable=%p period=%p duty=%p" " required path is NULL", _export_path, _enable_path, _period_path, _duty_path); @@ -269,7 +269,7 @@ char *PWM_Sysfs_Bebop::_generate_period_path(uint8_t channel) PWM_Sysfs_Bebop::PWM_Sysfs_Bebop(uint8_t channel) : PWM_Sysfs_Base(_generate_export_path(), - NULL, + nullptr, _generate_enable_path(channel), _generate_duty_path(channel), _generate_period_path(channel), diff --git a/libraries/AP_HAL_Linux/PWM_Sysfs.h b/libraries/AP_HAL_Linux/PWM_Sysfs.h index 07bd02838a..89a3cfc9f2 100644 --- a/libraries/AP_HAL_Linux/PWM_Sysfs.h +++ b/libraries/AP_HAL_Linux/PWM_Sysfs.h @@ -46,11 +46,11 @@ protected: private: uint32_t _nsec_duty_cycle_value = 0; int _duty_cycle_fd = -1; - char *_export_path = NULL; - char *_polarity_path = NULL; - char *_enable_path = NULL; - char *_duty_path = NULL; - char *_period_path = NULL; + char *_export_path = nullptr; + char *_polarity_path = nullptr; + char *_enable_path = nullptr; + char *_duty_path = nullptr; + char *_period_path = nullptr; }; class PWM_Sysfs : public PWM_Sysfs_Base { diff --git a/libraries/AP_HAL_Linux/RCInput.cpp b/libraries/AP_HAL_Linux/RCInput.cpp index 1e15ea7d2a..5f44a46b67 100644 --- a/libraries/AP_HAL_Linux/RCInput.cpp +++ b/libraries/AP_HAL_Linux/RCInput.cpp @@ -320,7 +320,7 @@ void RCInput::_process_rc_pulse(uint16_t width_s0, uint16_t width_s1) #if 0 // useful for debugging static FILE *rclog; - if (rclog == NULL) { + if (rclog == nullptr) { rclog = fopen("/tmp/rcin.log", "w"); } if (rclog) { diff --git a/libraries/AP_HAL_Linux/RCInput_115200.cpp b/libraries/AP_HAL_Linux/RCInput_115200.cpp index 5766d42421..47140996ae 100644 --- a/libraries/AP_HAL_Linux/RCInput_115200.cpp +++ b/libraries/AP_HAL_Linux/RCInput_115200.cpp @@ -87,7 +87,7 @@ void RCInput_115200::_timer_tick(void) tv.tv_usec = 0; // check if any bytes are available - if (select(fd+1, &fds, NULL, NULL, &tv) != 1) { + if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) { return; } diff --git a/libraries/AP_HAL_Linux/RCInput_RPI.cpp b/libraries/AP_HAL_Linux/RCInput_RPI.cpp index b1fe839460..c1076d5b0d 100644 --- a/libraries/AP_HAL_Linux/RCInput_RPI.cpp +++ b/libraries/AP_HAL_Linux/RCInput_RPI.cpp @@ -150,7 +150,7 @@ Memory_table::~Memory_table() void* Memory_table::get_page(void** const pages, uint32_t addr) const { if (addr >= PAGE_SIZE * _page_count) { - return NULL; + return nullptr; } return (uint8_t*)pages[(uint32_t) addr / 4096] + addr % 4096; } @@ -166,7 +166,7 @@ void* Memory_table::get_virt_addr(const uint32_t phys_addr) const return (void*) ((uintptr_t) _virt_pages[i] + (phys_addr & 0xFFF)); } } - return NULL; + return nullptr; } // FIXME: in-congruent function style see above @@ -221,9 +221,9 @@ void* RCInput_RPI::map_peripheral(uint32_t base, uint32_t len) if (fd < 0) { printf("Failed to open /dev/mem: %m\n"); - return NULL; + return nullptr; } - vaddr = mmap(NULL, len, PROT_READ|PROT_WRITE, MAP_SHARED, fd, base); + vaddr = mmap(nullptr, len, PROT_READ|PROT_WRITE, MAP_SHARED, fd, base); if (vaddr == MAP_FAILED) { printf("rpio-pwm: Failed to map peripheral at 0x%08x: %m\n", base); } @@ -472,7 +472,7 @@ void RCInput_RPI::_timer_tick() dma_cb_t* ad = (dma_cb_t*) con_blocks->get_virt_addr(dma_reg[RCIN_RPI_DMA_CONBLK_AD | RCIN_RPI_DMA_CHANNEL << 8]); for(j = 1; j >= -1; j--){ x = circle_buffer->get_virt_addr((ad + j)->dst); - if(x != NULL) { + if(x != nullptr) { break;} } diff --git a/libraries/AP_HAL_Linux/RCInput_SBUS.cpp b/libraries/AP_HAL_Linux/RCInput_SBUS.cpp index 209c6a2bdd..312e3a1193 100644 --- a/libraries/AP_HAL_Linux/RCInput_SBUS.cpp +++ b/libraries/AP_HAL_Linux/RCInput_SBUS.cpp @@ -100,7 +100,7 @@ void RCInput_SBUS::_timer_tick(void) // as VMIN is SBUS_FRAME_SIZE the select won't return unless there is // at least SBUS_FRAME_SIZE bytes available - if (select(fd+1, &fds, NULL, NULL, &tv) != 1) { + if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) { return; } diff --git a/libraries/AP_HAL_Linux/RCOutput_Bebop.cpp b/libraries/AP_HAL_Linux/RCOutput_Bebop.cpp index bad5188d23..472a7bebc5 100644 --- a/libraries/AP_HAL_Linux/RCOutput_Bebop.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_Bebop.cpp @@ -301,7 +301,7 @@ void RCOutput_Bebop::init() pthread_condattr_t cond_attr; /* Initialize thread, cond, and mutex */ - ret = pthread_mutex_init(&_mutex, NULL); + ret = pthread_mutex_init(&_mutex, nullptr); if (ret != 0) { perror("RCout_Bebop: failed to init mutex\n"); return; @@ -419,7 +419,7 @@ void* RCOutput_Bebop::_control_thread(void *arg) { RCOutput_Bebop* rcout = (RCOutput_Bebop *) arg; rcout->_run_rcout(); - return NULL; + return nullptr; } void RCOutput_Bebop::_run_rcout() diff --git a/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp b/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp index 469d905926..602e0893d4 100644 --- a/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_PCA9685.cpp @@ -61,7 +61,7 @@ RCOutput_PCA9685::RCOutput_PCA9685(AP_HAL::OwnPtr dev, uint8_t channel_offset, int16_t oe_pin_number) : _dev(std::move(dev)), - _enable_pin(NULL), + _enable_pin(nullptr), _frequency(50), _pulses_buffer(new uint16_t[PWM_CHAN_COUNT - channel_offset]), _external_clock(external_clock), diff --git a/libraries/AP_HAL_Linux/RPIOUARTDriver.cpp b/libraries/AP_HAL_Linux/RPIOUARTDriver.cpp index 8fafcab943..ca4ee33e72 100644 --- a/libraries/AP_HAL_Linux/RPIOUARTDriver.cpp +++ b/libraries/AP_HAL_Linux/RPIOUARTDriver.cpp @@ -55,7 +55,7 @@ void RPIOUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) { //hal.console->printf("[RPIOUARTDriver]: begin \n"); - if (device_path != NULL) { + if (device_path != nullptr) { UARTDriver::begin(b,rxS,txS); if ( is_initialized()) { _external = true; diff --git a/libraries/AP_HAL_Linux/SPIUARTDriver.cpp b/libraries/AP_HAL_Linux/SPIUARTDriver.cpp index d5d4b84961..807511e9c2 100644 --- a/libraries/AP_HAL_Linux/SPIUARTDriver.cpp +++ b/libraries/AP_HAL_Linux/SPIUARTDriver.cpp @@ -27,7 +27,7 @@ SPIUARTDriver::SPIUARTDriver() void SPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) { - if (device_path != NULL) { + if (device_path != nullptr) { UARTDriver::begin(b, rxS, txS); if (is_initialized()) { _external = true; @@ -52,10 +52,10 @@ void SPIUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) _readbuf.set_size(rxS); _writebuf.set_size(txS); - if (_buffer == NULL) { + if (_buffer == nullptr) { /* Do not allocate new buffer, if we're just changing speed */ _buffer = new uint8_t[rxS]; - if (_buffer == NULL) { + if (_buffer == nullptr) { hal.console->printf("Not enough memory\n"); AP_HAL::panic("Not enough memory\n"); } diff --git a/libraries/AP_HAL_Linux/Scheduler.cpp b/libraries/AP_HAL_Linux/Scheduler.cpp index 3065a1bb8e..0ff2d8fe57 100644 --- a/libraries/AP_HAL_Linux/Scheduler.cpp +++ b/libraries/AP_HAL_Linux/Scheduler.cpp @@ -323,7 +323,7 @@ void Scheduler::_timer_task() _timer_semaphore.give(); // and the failsafe, if one is setup - if (_failsafe != NULL) { + if (_failsafe != nullptr) { _failsafe(); } diff --git a/libraries/AP_HAL_Linux/Semaphores.h b/libraries/AP_HAL_Linux/Semaphores.h index fdfc5e5e0f..c323f543ce 100644 --- a/libraries/AP_HAL_Linux/Semaphores.h +++ b/libraries/AP_HAL_Linux/Semaphores.h @@ -11,7 +11,7 @@ namespace Linux { class Semaphore : public AP_HAL::Semaphore { public: Semaphore() { - pthread_mutex_init(&_lock, NULL); + pthread_mutex_init(&_lock, nullptr); } bool give(); bool take(uint32_t timeout_ms); diff --git a/libraries/AP_HAL_Linux/TCPServerDevice.cpp b/libraries/AP_HAL_Linux/TCPServerDevice.cpp index 1aeef59169..d74b9c64e1 100644 --- a/libraries/AP_HAL_Linux/TCPServerDevice.cpp +++ b/libraries/AP_HAL_Linux/TCPServerDevice.cpp @@ -18,15 +18,15 @@ TCPServerDevice::TCPServerDevice(const char *ip, uint16_t port, bool wait): TCPServerDevice::~TCPServerDevice() { - if (sock != NULL) { + if (sock != nullptr) { delete sock; - sock = NULL; + sock = nullptr; } } ssize_t TCPServerDevice::write(const uint8_t *buf, uint16_t n) { - if (sock == NULL) { + if (sock == nullptr) { return -1; } return sock->send(buf, n); @@ -38,20 +38,20 @@ ssize_t TCPServerDevice::write(const uint8_t *buf, uint16_t n) */ ssize_t TCPServerDevice::read(uint8_t *buf, uint16_t n) { - if (sock == NULL) { + if (sock == nullptr) { sock = listener.accept(0); - if (sock != NULL) { + if (sock != nullptr) { sock->set_blocking(_blocking); } } - if (sock == NULL) { + if (sock == nullptr) { return -1; } ssize_t ret = sock->recv(buf, n, 1); if (ret == 0) { // EOF, go back to waiting for a new connection delete sock; - sock = NULL; + sock = nullptr; return -1; } return ret; @@ -89,7 +89,7 @@ bool TCPServerDevice::open() ::printf("Waiting for connection on %s:%u ....\n", _ip, (unsigned)_port); ::fflush(stdout); - while (sock == NULL) { + while (sock == nullptr) { sock = listener.accept(1000); } sock->set_blocking(_blocking); @@ -102,9 +102,9 @@ bool TCPServerDevice::open() bool TCPServerDevice::close() { - if (sock != NULL) { + if (sock != nullptr) { delete sock; - sock = NULL; + sock = nullptr; } return true; } diff --git a/libraries/AP_HAL_Linux/TCPServerDevice.h b/libraries/AP_HAL_Linux/TCPServerDevice.h index 488b45b5bc..757e336df2 100644 --- a/libraries/AP_HAL_Linux/TCPServerDevice.h +++ b/libraries/AP_HAL_Linux/TCPServerDevice.h @@ -17,7 +17,7 @@ public: private: SocketAPM listener{false}; - SocketAPM *sock = NULL; + SocketAPM *sock = nullptr; const char *_ip; uint16_t _port; bool _wait; diff --git a/libraries/AP_HAL_Linux/ToneAlarm_Raspilot.cpp b/libraries/AP_HAL_Linux/ToneAlarm_Raspilot.cpp index f8ef057cfb..a02132cced 100644 --- a/libraries/AP_HAL_Linux/ToneAlarm_Raspilot.cpp +++ b/libraries/AP_HAL_Linux/ToneAlarm_Raspilot.cpp @@ -73,7 +73,7 @@ bool ToneAlarm_Raspilot::init() // mmap GPIO void *pwm_map = mmap( - NULL, // Any adddress in our space will do + nullptr, // Any adddress in our space will do BLOCK_SIZE, // Map length PROT_READ|PROT_WRITE, // Enable reading & writting to mapped memory MAP_SHARED, // Shared with other processes @@ -82,7 +82,7 @@ bool ToneAlarm_Raspilot::init() ); void *clk_map = mmap( - NULL, // Any adddress in our space will do + nullptr, // Any adddress in our space will do BLOCK_SIZE, // Map length PROT_READ|PROT_WRITE, // Enable reading & writting to mapped memory MAP_SHARED, // Shared with other processes diff --git a/libraries/AP_HAL_Linux/UARTDriver.cpp b/libraries/AP_HAL_Linux/UARTDriver.cpp index c03061d478..c807cb497b 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.cpp +++ b/libraries/AP_HAL_Linux/UARTDriver.cpp @@ -32,7 +32,7 @@ extern const AP_HAL::HAL& hal; using namespace Linux; UARTDriver::UARTDriver(bool default_console) : - device_path(NULL), + device_path(nullptr), _packetise(false), _device{new ConsoleDevice()} { @@ -60,10 +60,10 @@ void UARTDriver::begin(uint32_t b) void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS) { if (!_initialised) { - if (device_path == NULL && _console) { + if (device_path == nullptr && _console) { _device = new ConsoleDevice(); } else { - if (device_path == NULL) { + if (device_path == nullptr) { return; } @@ -139,38 +139,38 @@ AP_HAL::OwnPtr UARTDriver::_parseDevicePath(const char *arg) char *devstr = strdup(arg); - if (devstr == NULL) { + if (devstr == nullptr) { return nullptr; } - char *saveptr = NULL; + char *saveptr = nullptr; char *protocol, *ip, *port, *flag; protocol = strtok_r(devstr, ":", &saveptr); - ip = strtok_r(NULL, ":", &saveptr); - port = strtok_r(NULL, ":", &saveptr); - flag = strtok_r(NULL, ":", &saveptr); + ip = strtok_r(nullptr, ":", &saveptr); + port = strtok_r(nullptr, ":", &saveptr); + flag = strtok_r(nullptr, ":", &saveptr); - if (ip == NULL || port == NULL) { + if (ip == nullptr || port == nullptr) { free(devstr); return nullptr; } if (_ip) { free(_ip); - _ip = NULL; + _ip = nullptr; } if (_flag) { free(_flag); - _flag = NULL; + _flag = nullptr; } _base_port = (uint16_t) atoi(port); _ip = strdup(ip); /* Optional flag for TCP */ - if (flag != NULL) { + if (flag != nullptr) { _flag = strdup(flag); } diff --git a/libraries/AP_HAL_Linux/Util.cpp b/libraries/AP_HAL_Linux/Util.cpp index bb35a2d635..9234c8dda3 100644 --- a/libraries/AP_HAL_Linux/Util.cpp +++ b/libraries/AP_HAL_Linux/Util.cpp @@ -186,16 +186,16 @@ int Util::get_hw_arm32() { char buffer[MAX_SIZE_LINE] = { 0 }; FILE *f = fopen("/proc/cpuinfo", "r"); - if (f == NULL) { + if (f == nullptr) { return -errno; } - while (fgets(buffer, MAX_SIZE_LINE, f) != NULL) { - if (strstr(buffer, "Hardware") == NULL) { + while (fgets(buffer, MAX_SIZE_LINE, f) != nullptr) { + if (strstr(buffer, "Hardware") == nullptr) { continue; } for (uint8_t i = 0; i < UTIL_NUM_HARDWARES; i++) { - if (strstr(buffer, _hw_names[i]) == NULL) { + if (strstr(buffer, _hw_names[i]) == nullptr) { continue; } fclose(f); diff --git a/libraries/AP_HAL_Linux/Util.h b/libraries/AP_HAL_Linux/Util.h index 706f7886c9..e9c7b867d9 100644 --- a/libraries/AP_HAL_Linux/Util.h +++ b/libraries/AP_HAL_Linux/Util.h @@ -105,8 +105,8 @@ private: Heat *_heat; int saved_argc; char* const *saved_argv; - const char* custom_log_directory = NULL; - const char* custom_terrain_directory = NULL; + const char* custom_log_directory = nullptr; + const char* custom_terrain_directory = nullptr; static const char *_hw_names[UTIL_NUM_HARDWARES]; }; diff --git a/libraries/AP_HAL_Linux/VideoIn.cpp b/libraries/AP_HAL_Linux/VideoIn.cpp index 154d912962..cf7378b962 100644 --- a/libraries/AP_HAL_Linux/VideoIn.cpp +++ b/libraries/AP_HAL_Linux/VideoIn.cpp @@ -67,7 +67,7 @@ bool VideoIn::open_device(const char *device_path, uint32_t memtype) int ret; _fd = -1; - _buffers = NULL; + _buffers = nullptr; _fd = open(device_path, O_RDWR); _memtype = memtype; if (_fd < 0) { @@ -115,7 +115,7 @@ bool VideoIn::allocate_buffers(uint32_t nbufs) } buffers = (struct buffer *)malloc(rb.count * sizeof buffers[0]); - if (buffers == NULL) { + if (buffers == nullptr) { hal.console->printf("Unable to allocate buffers\n"); return false; } diff --git a/libraries/AP_HAL_Linux/examples/GPIOTest/GPIOTest.cpp b/libraries/AP_HAL_Linux/examples/GPIOTest/GPIOTest.cpp index bfa2af4730..2764637167 100644 --- a/libraries/AP_HAL_Linux/examples/GPIOTest/GPIOTest.cpp +++ b/libraries/AP_HAL_Linux/examples/GPIOTest/GPIOTest.cpp @@ -25,7 +25,7 @@ int parse_gpio_pin_number(uint8_t argc, const Menu::arg *argv) { } static int8_t test_gpio_input(uint8_t argc, const Menu::arg *argv, bool use_channel) { - AP_HAL::DigitalSource *ch = NULL; + AP_HAL::DigitalSource *ch = nullptr; int pin = parse_gpio_pin_number(argc, argv); if (pin <= 0) return -1; @@ -46,7 +46,7 @@ static int8_t test_gpio_input(uint8_t argc, const Menu::arg *argv, bool use_chan } static int8_t test_gpio_output(uint8_t argc, const Menu::arg *argv, bool use_channel) { - AP_HAL::DigitalSource *ch = NULL; + AP_HAL::DigitalSource *ch = nullptr; int pin = parse_gpio_pin_number(argc, argv); if (pin <= 0) return -1; diff --git a/libraries/AP_HAL_Linux/qflight/dsp_functions.cpp b/libraries/AP_HAL_Linux/qflight/dsp_functions.cpp index d5da21293e..a6176572eb 100644 --- a/libraries/AP_HAL_Linux/qflight/dsp_functions.cpp +++ b/libraries/AP_HAL_Linux/qflight/dsp_functions.cpp @@ -129,7 +129,7 @@ static void *mpu_data_ready(void *ctx) int ret = mpu9x50_get_data(&data); if (ret != 0) { - return NULL; + return nullptr; } DSPBuffer::IMU::BUF b; b.timestamp = data.timestamp; @@ -163,7 +163,7 @@ static void *mpu_data_ready(void *ctx) } } - return NULL; + return nullptr; } static void mpu9250_startup(void) @@ -172,7 +172,7 @@ static void mpu9250_startup(void) if (init_mpu9250() != 0) { return; } - mpu9x50_register_interrupt(65, mpu_data_ready, NULL); + mpu9x50_register_interrupt(65, mpu_data_ready, nullptr); } } diff --git a/libraries/AP_HAL_PX4/AnalogIn.cpp b/libraries/AP_HAL_PX4/AnalogIn.cpp index 8f02df9ad2..9a4d9687c7 100644 --- a/libraries/AP_HAL_PX4/AnalogIn.cpp +++ b/libraries/AP_HAL_PX4/AnalogIn.cpp @@ -257,7 +257,7 @@ void PX4AnalogIn::_timer_tick(void) struct adc_msg_s buf_adc[PX4_ANALOG_MAX_CHANNELS]; // cope with initial setup of stop pin - if (_channels[_current_stop_pin_i] == NULL || + if (_channels[_current_stop_pin_i] == nullptr || _channels[_current_stop_pin_i]->_stop_pin == -1) { next_stop_pin(); } @@ -281,7 +281,7 @@ void PX4AnalogIn::_timer_tick(void) (unsigned)buf_adc[i].am_data); for (uint8_t j=0; j_pin) { + if (c != nullptr && buf_adc[i].am_channel == c->_pin) { // add a value if either there is no stop pin, or // the stop pin has been settling for enough time if (c->_stop_pin == -1 || @@ -308,7 +308,7 @@ void PX4AnalogIn::_timer_tick(void) _battery_timestamp = battery.timestamp; for (uint8_t j=0; j_pin == PX4_ANALOG_ORB_BATTERY_VOLTAGE_PIN) { c->_add_value(battery.voltage_v / PX4_VOLTAGE_SCALING, 0); } @@ -335,7 +335,7 @@ void PX4AnalogIn::_timer_tick(void) _servorail_voltage = servorail.voltage_v; for (uint8_t j=0; j_pin == PX4_ANALOG_ORB_SERVO_VOLTAGE_PIN) { c->_add_value(servorail.voltage_v / PX4_VOLTAGE_SCALING, 0); } @@ -373,13 +373,13 @@ void PX4AnalogIn::_timer_tick(void) AP_HAL::AnalogSource* PX4AnalogIn::channel(int16_t pin) { for (uint8_t j=0; jprintln("Out of analog channels"); - return NULL; + return nullptr; } #endif // CONFIG_HAL_BOARD diff --git a/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp b/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp index 223bb37b14..cd493ba5c4 100644 --- a/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp +++ b/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp @@ -91,7 +91,7 @@ HAL_PX4::HAL_PX4() : &rcoutDriver, /* rcoutput */ &schedulerInstance, /* scheduler */ &utilInstance, /* util */ - NULL) /* no onboard optical flow */ + nullptr) /* no onboard optical flow */ {} bool _px4_thread_should_exit = false; /**< Daemon exit flag */ @@ -170,7 +170,7 @@ static int main_loop(int argc, char **argv) will only ever be called if a loop() call runs for more than 0.1 second */ - hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)loop_overtime, NULL); + hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)loop_overtime, nullptr); g_callbacks->loop(); @@ -248,7 +248,7 @@ void HAL_PX4::run(int argc, char * const argv[], Callbacks* callbacks) const APM_MAIN_PRIORITY, APM_MAIN_THREAD_STACK_SIZE, main_loop, - NULL); + nullptr); exit(0); } diff --git a/libraries/AP_HAL_PX4/NSHShellStream.cpp b/libraries/AP_HAL_PX4/NSHShellStream.cpp index d1c38f9338..052d749105 100644 --- a/libraries/AP_HAL_PX4/NSHShellStream.cpp +++ b/libraries/AP_HAL_PX4/NSHShellStream.cpp @@ -31,7 +31,7 @@ void NSHShellStream::shell_thread(void *arg) dup2(nsh->child.out, 1); dup2(nsh->child.out, 2); - nsh_consolemain(0, NULL); + nsh_consolemain(0, nullptr); nsh->shell_stdin = -1; nsh->shell_stdout = -1; diff --git a/libraries/AP_HAL_PX4/RCInput.cpp b/libraries/AP_HAL_PX4/RCInput.cpp index 7a9e161f80..6d745b1731 100644 --- a/libraries/AP_HAL_PX4/RCInput.cpp +++ b/libraries/AP_HAL_PX4/RCInput.cpp @@ -20,7 +20,7 @@ void PX4RCInput::init() AP_HAL::panic("Unable to subscribe to input_rc"); } clear_overrides(); - pthread_mutex_init(&rcin_mutex, NULL); + pthread_mutex_init(&rcin_mutex, nullptr); } bool PX4RCInput::new_input() diff --git a/libraries/AP_HAL_PX4/RCOutput.cpp b/libraries/AP_HAL_PX4/RCOutput.cpp index 2f50292d28..c857e9631f 100644 --- a/libraries/AP_HAL_PX4/RCOutput.cpp +++ b/libraries/AP_HAL_PX4/RCOutput.cpp @@ -71,10 +71,10 @@ void PX4RCOutput::init() } // publish actuator vaules on demand - _actuator_direct_pub = NULL; + _actuator_direct_pub = nullptr; // and armed state - _actuator_armed_pub = NULL; + _actuator_armed_pub = nullptr; } @@ -391,7 +391,7 @@ void PX4RCOutput::_arm_actuators(bool arm) _armed.lockdown = false; _armed.force_failsafe = false; - if (_actuator_armed_pub == NULL) { + if (_actuator_armed_pub == nullptr) { _actuator_armed_pub = orb_advertise(ORB_ID(actuator_armed), &_armed); } else { orb_publish(ORB_ID(actuator_armed), _actuator_armed_pub, &_armed); @@ -433,7 +433,7 @@ void PX4RCOutput::_publish_actuators(void) actuators.values[i] = actuators.values[i]*2 - 1; } - if (_actuator_direct_pub == NULL) { + if (_actuator_direct_pub == nullptr) { _actuator_direct_pub = orb_advertise(ORB_ID(actuator_direct), &actuators); } else { orb_publish(ORB_ID(actuator_direct), _actuator_direct_pub, &actuators); diff --git a/libraries/AP_HAL_PX4/RCOutput.h b/libraries/AP_HAL_PX4/RCOutput.h index 1876cd881a..5c6eddbf09 100644 --- a/libraries/AP_HAL_PX4/RCOutput.h +++ b/libraries/AP_HAL_PX4/RCOutput.h @@ -58,8 +58,8 @@ private: } _outputs[ORB_MULTI_MAX_INSTANCES] {}; actuator_armed_s _armed; - orb_advert_t _actuator_direct_pub = NULL; - orb_advert_t _actuator_armed_pub = NULL; + orb_advert_t _actuator_direct_pub = nullptr; + orb_advert_t _actuator_armed_pub = nullptr; uint16_t _esc_pwm_min = 0; uint16_t _esc_pwm_max = 0; diff --git a/libraries/AP_HAL_PX4/Scheduler.cpp b/libraries/AP_HAL_PX4/Scheduler.cpp index d001730581..eea164fce3 100644 --- a/libraries/AP_HAL_PX4/Scheduler.cpp +++ b/libraries/AP_HAL_PX4/Scheduler.cpp @@ -133,7 +133,7 @@ void PX4Scheduler::delay_microseconds_boost(uint16_t usec) sem_init(&wait_semaphore, 0, 0); hrt_call_after(&wait_call, usec, (hrt_callout)sem_post_boost, &wait_semaphore); sem_wait(&wait_semaphore); - hrt_call_after(&wait_call, APM_MAIN_PRIORITY_BOOST_USEC, (hrt_callout)set_normal_priority, NULL); + hrt_call_after(&wait_call, APM_MAIN_PRIORITY_BOOST_USEC, (hrt_callout)set_normal_priority, nullptr); } void PX4Scheduler::delay(uint16_t ms) @@ -249,7 +249,7 @@ void PX4Scheduler::_run_timers(bool called_from_timer_thread) } // and the failsafe, if one is setup - if (_failsafe != NULL) { + if (_failsafe != nullptr) { _failsafe(); } @@ -267,7 +267,7 @@ void *PX4Scheduler::_timer_thread(void *arg) uint32_t last_ran_overtime = 0; while (!sched->_hal_initialized) { - poll(NULL, 0, 1); + poll(nullptr, 0, 1); } while (!_px4_thread_should_exit) { sched->delay_microseconds_semaphore(1000); @@ -291,7 +291,7 @@ void *PX4Scheduler::_timer_thread(void *arg) #endif } } - return NULL; + return nullptr; } void PX4Scheduler::_run_io(void) @@ -318,7 +318,7 @@ void *PX4Scheduler::_uart_thread(void *arg) PX4Scheduler *sched = (PX4Scheduler *)arg; while (!sched->_hal_initialized) { - poll(NULL, 0, 1); + poll(nullptr, 0, 1); } while (!_px4_thread_should_exit) { sched->delay_microseconds_semaphore(1000); @@ -331,7 +331,7 @@ void *PX4Scheduler::_uart_thread(void *arg) ((PX4UARTDriver *)hal.uartE)->_timer_tick(); ((PX4UARTDriver *)hal.uartF)->_timer_tick(); } - return NULL; + return nullptr; } void *PX4Scheduler::_io_thread(void *arg) @@ -339,17 +339,17 @@ void *PX4Scheduler::_io_thread(void *arg) PX4Scheduler *sched = (PX4Scheduler *)arg; while (!sched->_hal_initialized) { - poll(NULL, 0, 1); + poll(nullptr, 0, 1); } while (!_px4_thread_should_exit) { - poll(NULL, 0, 1); + poll(nullptr, 0, 1); // run registered IO processes perf_begin(sched->_perf_io_timers); sched->_run_io(); perf_end(sched->_perf_io_timers); } - return NULL; + return nullptr; } void *PX4Scheduler::_storage_thread(void *arg) @@ -357,17 +357,17 @@ void *PX4Scheduler::_storage_thread(void *arg) PX4Scheduler *sched = (PX4Scheduler *)arg; while (!sched->_hal_initialized) { - poll(NULL, 0, 1); + poll(nullptr, 0, 1); } while (!_px4_thread_should_exit) { - poll(NULL, 0, 10); + poll(nullptr, 0, 10); // process any pending storage writes perf_begin(sched->_perf_storage_timer); ((PX4Storage *)hal.storage)->_timer_tick(); perf_end(sched->_perf_storage_timer); } - return NULL; + return nullptr; } bool PX4Scheduler::in_timerprocess() diff --git a/libraries/AP_HAL_PX4/Semaphores.h b/libraries/AP_HAL_PX4/Semaphores.h index fc828e61f4..3e16f81515 100644 --- a/libraries/AP_HAL_PX4/Semaphores.h +++ b/libraries/AP_HAL_PX4/Semaphores.h @@ -9,7 +9,7 @@ class PX4::Semaphore : public AP_HAL::Semaphore { public: Semaphore() { - pthread_mutex_init(&_lock, NULL); + pthread_mutex_init(&_lock, nullptr); } bool give(); bool take(uint32_t timeout_ms); diff --git a/libraries/AP_HAL_PX4/Util.cpp b/libraries/AP_HAL_PX4/Util.cpp index eaa6d59f14..953d61d037 100644 --- a/libraries/AP_HAL_PX4/Util.cpp +++ b/libraries/AP_HAL_PX4/Util.cpp @@ -61,7 +61,7 @@ bool PX4Util::run_debug_shell(AP_HAL::BetterStream *stream) dup2(fd, 1); dup2(fd, 2); - nsh_consolemain(0, NULL); + nsh_consolemain(0, nullptr); // this shouldn't happen hal.console->printf("shell exited\n"); @@ -152,7 +152,7 @@ PX4Util::perf_counter_t PX4Util::perf_alloc(PX4Util::perf_counter_type t, const px4_t = ::PC_INTERVAL; break; default: - return NULL; + return nullptr; } return (perf_counter_t)::perf_alloc(px4_t, name); } diff --git a/libraries/AP_HAL_QURT/HAL_QURT_Class.cpp b/libraries/AP_HAL_QURT/HAL_QURT_Class.cpp index a2454b7a7f..ee34b1d33c 100644 --- a/libraries/AP_HAL_QURT/HAL_QURT_Class.cpp +++ b/libraries/AP_HAL_QURT/HAL_QURT_Class.cpp @@ -55,7 +55,7 @@ HAL_QURT::HAL_QURT() : &uartCDriver, &uartDDriver, &uartEDriver, - NULL, // uartF + nullptr, // uartF &i2c_mgr_instance, &spiDeviceManager, &analogIn, @@ -66,7 +66,7 @@ HAL_QURT::HAL_QURT() : &rcoutDriver, &schedulerInstance, &utilInstance, - NULL) + nullptr) { } diff --git a/libraries/AP_HAL_QURT/Scheduler.cpp b/libraries/AP_HAL_QURT/Scheduler.cpp index a25493418d..18870873e5 100644 --- a/libraries/AP_HAL_QURT/Scheduler.cpp +++ b/libraries/AP_HAL_QURT/Scheduler.cpp @@ -171,7 +171,7 @@ void Scheduler::_run_timers(bool called_from_timer_thread) } // and the failsafe, if one is setup - if (_failsafe != NULL) { + if (_failsafe != nullptr) { _failsafe(); } @@ -203,7 +203,7 @@ void *Scheduler::_timer_thread(void *arg) hal.console->printf("Overtime in task %d\n", (int)AP_Scheduler::current_task); } } - return NULL; + return nullptr; } void Scheduler::_run_io(void) @@ -242,7 +242,7 @@ void *Scheduler::_uart_thread(void *arg) ((UARTDriver *)hal.uartD)->timer_tick(); ((UARTDriver *)hal.uartE)->timer_tick(); } - return NULL; + return nullptr; } void *Scheduler::_io_thread(void *arg) @@ -258,7 +258,7 @@ void *Scheduler::_io_thread(void *arg) // run registered IO processes sched->_run_io(); } - return NULL; + return nullptr; } bool Scheduler::in_timerprocess() diff --git a/libraries/AP_HAL_QURT/Semaphores.h b/libraries/AP_HAL_QURT/Semaphores.h index 89ec68346f..a3fe08807c 100644 --- a/libraries/AP_HAL_QURT/Semaphores.h +++ b/libraries/AP_HAL_QURT/Semaphores.h @@ -9,7 +9,7 @@ class QURT::Semaphore : public AP_HAL::Semaphore { public: Semaphore() { - pthread_mutex_init(&_lock, NULL); + pthread_mutex_init(&_lock, nullptr); } bool give(); bool take(uint32_t timeout_ms); diff --git a/libraries/AP_HAL_QURT/dsp_main.cpp b/libraries/AP_HAL_QURT/dsp_main.cpp index bd381f4acb..d57b2635c8 100644 --- a/libraries/AP_HAL_QURT/dsp_main.cpp +++ b/libraries/AP_HAL_QURT/dsp_main.cpp @@ -41,7 +41,7 @@ static void *main_thread(void *cmdptr) argv[argc] = nullptr; ArduPilot_main(argc, argv); - return NULL; + return nullptr; } diff --git a/libraries/AP_HAL_QURT/mainapp/getifaddrs.cpp b/libraries/AP_HAL_QURT/mainapp/getifaddrs.cpp index 860b7ceb30..e1d73d09dd 100644 --- a/libraries/AP_HAL_QURT/mainapp/getifaddrs.cpp +++ b/libraries/AP_HAL_QURT/mainapp/getifaddrs.cpp @@ -35,7 +35,7 @@ void freeifaddrs(struct ifaddrs *ifp) { - if (ifp != NULL) { + if (ifp != nullptr) { free(ifp->ifa_name); free(ifp->ifa_addr); free(ifp->ifa_netmask); @@ -51,8 +51,8 @@ static struct sockaddr *sockaddr_dup(struct sockaddr *sa) socklen_t socklen; socklen = sizeof(struct sockaddr_storage); ret = (struct sockaddr *)calloc(1, socklen); - if (ret == NULL) - return NULL; + if (ret == nullptr) + return nullptr; memcpy(ret, sa, socklen); return ret; } @@ -67,11 +67,11 @@ int getifaddrs(struct ifaddrs **ifap) struct ifconf ifc; char buff[8192]; int fd, i, n; - struct ifreq *ifr=NULL; + struct ifreq *ifr=nullptr; struct ifaddrs *curif; - struct ifaddrs *lastif = NULL; + struct ifaddrs *lastif = nullptr; - *ifap = NULL; + *ifap = nullptr; if ((fd = socket(AF_INET, SOCK_DGRAM, 0)) == -1) { return -1; @@ -98,27 +98,27 @@ int getifaddrs(struct ifaddrs **ifap) } curif = (struct ifaddrs *)calloc(1, sizeof(struct ifaddrs)); - if (curif == NULL) { + if (curif == nullptr) { freeifaddrs(*ifap); close(fd); return -1; } curif->ifa_name = strdup(ifr[i].ifr_name); - if (curif->ifa_name == NULL) { + if (curif->ifa_name == nullptr) { free(curif); freeifaddrs(*ifap); close(fd); return -1; } curif->ifa_flags = ifr[i].ifr_flags; - curif->ifa_dstaddr = NULL; - curif->ifa_data = NULL; - curif->ifa_next = NULL; + curif->ifa_dstaddr = nullptr; + curif->ifa_data = nullptr; + curif->ifa_next = nullptr; - curif->ifa_addr = NULL; + curif->ifa_addr = nullptr; if (ioctl(fd, SIOCGIFADDR, &ifr[i]) != -1) { curif->ifa_addr = sockaddr_dup(&ifr[i].ifr_addr); - if (curif->ifa_addr == NULL) { + if (curif->ifa_addr == nullptr) { free(curif->ifa_name); free(curif); freeifaddrs(*ifap); @@ -127,11 +127,11 @@ int getifaddrs(struct ifaddrs **ifap) } } - curif->ifa_netmask = NULL; + curif->ifa_netmask = nullptr; if (ioctl(fd, SIOCGIFNETMASK, &ifr[i]) != -1) { curif->ifa_netmask = sockaddr_dup(&ifr[i].ifr_addr); - if (curif->ifa_netmask == NULL) { - if (curif->ifa_addr != NULL) { + if (curif->ifa_netmask == nullptr) { + if (curif->ifa_addr != nullptr) { free(curif->ifa_addr); } free(curif->ifa_name); @@ -142,7 +142,7 @@ int getifaddrs(struct ifaddrs **ifap) } } - if (lastif == NULL) { + if (lastif == nullptr) { *ifap = curif; } else { lastif->ifa_next = curif; @@ -157,9 +157,9 @@ int getifaddrs(struct ifaddrs **ifap) const char *get_ipv4_broadcast(void) { - struct ifaddrs *ifap = NULL; + struct ifaddrs *ifap = nullptr; if (getifaddrs(&ifap) != 0) { - return NULL; + return nullptr; } struct ifaddrs *ia; for (ia=ifap; ia; ia=ia->ifa_next) { @@ -175,7 +175,7 @@ const char *get_ipv4_broadcast(void) return ret; } freeifaddrs(ifap); - return NULL; + return nullptr; } #ifdef MAIN_PROGRAM diff --git a/libraries/AP_HAL_QURT/mainapp/mainapp.cpp b/libraries/AP_HAL_QURT/mainapp/mainapp.cpp index 92529020c3..c2ea44b5df 100644 --- a/libraries/AP_HAL_QURT/mainapp/mainapp.cpp +++ b/libraries/AP_HAL_QURT/mainapp/mainapp.cpp @@ -84,7 +84,7 @@ static void get_storage(void) */ static void socket_check(void) { - static const char *bcast = NULL; + static const char *bcast = nullptr; uint8_t buf[300]; ssize_t ret = sock.recv(buf, sizeof(buf), 0); if (ret > 0) { @@ -102,9 +102,9 @@ static void socket_check(void) } } uint32_t nbytes; - if (bcast == NULL) { + if (bcast == nullptr) { bcast = get_ipv4_broadcast(); - if (bcast == NULL) { + if (bcast == nullptr) { bcast = "255.255.255.255"; } printf("Broadcasting to %s\n", bcast); diff --git a/libraries/AP_HAL_QURT/replace.cpp b/libraries/AP_HAL_QURT/replace.cpp index 6d89ba1a74..050d2c9b77 100644 --- a/libraries/AP_HAL_QURT/replace.cpp +++ b/libraries/AP_HAL_QURT/replace.cpp @@ -46,7 +46,7 @@ int vasprintf(char **ptr, const char *format, va_list ap) va_list ap2; va_copy(ap2, ap); - ret = vsnprintf(NULL, 0, format, ap2); + ret = vsnprintf(nullptr, 0, format, ap2); va_end(ap2); if (ret < 0) return ret; @@ -65,7 +65,7 @@ int asprintf(char **ptr, const char *format, ...) va_list ap; int ret; - *ptr = NULL; + *ptr = nullptr; va_start(ap, format); ret = vasprintf(ptr, format, ap); va_end(ap); diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index 569a8f1b3e..d2359f7aeb 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -27,15 +27,15 @@ void SITL_State::_set_param_default(const char *parm) { char *pdup = strdup(parm); char *p = strchr(pdup, '='); - if (p == NULL) { + if (p == nullptr) { printf("Please specify parameter as NAME=VALUE"); exit(1); } - float value = strtof(p+1, NULL); + float value = strtof(p+1, nullptr); *p = 0; enum ap_var_type var_type; AP_Param *vp = AP_Param::find(pdup, &var_type); - if (vp == NULL) { + if (vp == nullptr) { printf("Unknown parameter %s\n", pdup); exit(1); } @@ -85,7 +85,7 @@ void SITL_State::_sitl_setup(const char *home_str) #endif _optical_flow = (OpticalFlow *)AP_Param::find_object("FLOW"); - if (_sitl != NULL) { + if (_sitl != nullptr) { // setup some initial values #ifndef HIL_MODE _update_barometer(100); @@ -137,7 +137,7 @@ void SITL_State::_fdm_input_step(void) exit(1); } - if (_scheduler->interrupts_are_blocked() || _sitl == NULL) { + if (_scheduler->interrupts_are_blocked() || _sitl == nullptr) { return; } @@ -149,7 +149,7 @@ void SITL_State::_fdm_input_step(void) _scheduler->sitl_begin_atomic(); - if (_update_count == 0 && _sitl != NULL) { + if (_update_count == 0 && _sitl != nullptr) { _update_gps(0, 0, 0, 0, 0, 0, false); _update_barometer(0); _scheduler->timer_event(); @@ -157,7 +157,7 @@ void SITL_State::_fdm_input_step(void) return; } - if (_sitl != NULL) { + if (_sitl != nullptr) { _update_gps(_sitl->state.latitude, _sitl->state.longitude, _sitl->state.altitude, _sitl->state.speedN, _sitl->state.speedE, _sitl->state.speedD, @@ -288,10 +288,10 @@ void SITL_State::_fdm_input_local(void) } } - if (gimbal != NULL) { + if (gimbal != nullptr) { gimbal->update(); } - if (adsb != NULL) { + if (adsb != nullptr) { adsb->update(); } diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index b0e3c3192d..21d21bbb1f 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -113,8 +113,8 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) int opt; // default to CMAC const char *home_str = "-35.363261,149.165230,584,353"; - const char *model_str = NULL; - char *autotest_dir = NULL; + const char *model_str = nullptr; + char *autotest_dir = nullptr; float speedup = 1.0f; if (asprintf(&autotest_dir, SKETCHBOOK "/Tools/autotest") <= 0) { @@ -131,7 +131,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) _rcout_port = 5502; _simin_port = 5501; _fdm_address = "127.0.0.1"; - _client_address = NULL; + _client_address = nullptr; _instance = 0; enum long_options { @@ -211,7 +211,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) model_str = gopt.optarg; break; case 's': - speedup = strtof(gopt.optarg, NULL); + speedup = strtof(gopt.optarg, nullptr); break; case 'F': _fdm_address = gopt.optarg; diff --git a/libraries/AP_HAL_SITL/Scheduler.cpp b/libraries/AP_HAL_SITL/Scheduler.cpp index 47ab857add..3e076597f7 100644 --- a/libraries/AP_HAL_SITL/Scheduler.cpp +++ b/libraries/AP_HAL_SITL/Scheduler.cpp @@ -13,15 +13,15 @@ using namespace HALSITL; extern const AP_HAL::HAL& hal; -AP_HAL::Proc Scheduler::_failsafe = NULL; +AP_HAL::Proc Scheduler::_failsafe = nullptr; volatile bool Scheduler::_timer_suspended = false; volatile bool Scheduler::_timer_event_missed = false; -AP_HAL::MemberProc Scheduler::_timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {NULL}; +AP_HAL::MemberProc Scheduler::_timer_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {nullptr}; uint8_t Scheduler::_num_timer_procs = 0; bool Scheduler::_in_timer_proc = false; -AP_HAL::MemberProc Scheduler::_io_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {NULL}; +AP_HAL::MemberProc Scheduler::_io_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {nullptr}; uint8_t Scheduler::_num_io_procs = 0; bool Scheduler::_in_io_proc = false; @@ -129,7 +129,7 @@ void Scheduler::system_initialized() { // i386 with gcc doesn't work with FE_INVALID exceptions |= FE_INVALID; #endif - if (_sitlState->_sitl == NULL || _sitlState->_sitl->float_exception) { + if (_sitlState->_sitl == nullptr || _sitlState->_sitl->float_exception) { feenableexcept(exceptions); } else { feclearexcept(exceptions); @@ -162,7 +162,7 @@ void Scheduler::_run_timer_procs(bool called_from_isr) // need be. We assume the failsafe code can't // block. If it does then we will recurse and die when // we run out of stack - if (_failsafe != NULL) { + if (_failsafe != nullptr) { _failsafe(); } return; @@ -181,7 +181,7 @@ void Scheduler::_run_timer_procs(bool called_from_isr) } // and the failsafe, if one is setup - if (_failsafe != NULL) { + if (_failsafe != nullptr) { _failsafe(); } diff --git a/libraries/AP_HAL_SITL/Semaphores.h b/libraries/AP_HAL_SITL/Semaphores.h index b8f7b13781..f36d253dc4 100644 --- a/libraries/AP_HAL_SITL/Semaphores.h +++ b/libraries/AP_HAL_SITL/Semaphores.h @@ -9,7 +9,7 @@ class HALSITL::Semaphore : public AP_HAL::Semaphore { public: Semaphore() { - pthread_mutex_init(&_lock, NULL); + pthread_mutex_init(&_lock, nullptr); } bool give(); bool take(uint32_t timeout_ms); diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 5bd1383008..f0b903541c 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -67,17 +67,17 @@ void UARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace) tcpclient:192.168.2.15:5762 uart:/dev/ttyUSB0:57600 */ - char *saveptr = NULL; + char *saveptr = nullptr; char *s = strdup(path); char *devtype = strtok_r(s, ":", &saveptr); - char *args1 = strtok_r(NULL, ":", &saveptr); - char *args2 = strtok_r(NULL, ":", &saveptr); + char *args1 = strtok_r(nullptr, ":", &saveptr); + char *args2 = strtok_r(nullptr, ":", &saveptr); if (strcmp(devtype, "tcp") == 0) { uint16_t port = atoi(args1); bool wait = (args2 && strcmp(args2, "wait") == 0); _tcp_start_connection(port, wait); } else if (strcmp(devtype, "tcpclient") == 0) { - if (args2 == NULL) { + if (args2 == nullptr) { AP_HAL::panic("Invalid tcp client path: %s", path); } uint16_t port = atoi(args2); @@ -234,7 +234,7 @@ void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection) if (wait_for_connection) { fprintf(stdout, "Waiting for connection ....\n"); fflush(stdout); - _fd = accept(_listen_fd, NULL, NULL); + _fd = accept(_listen_fd, nullptr, nullptr); if (_fd == -1) { fprintf(stderr, "accept() error - %s", strerror(errno)); exit(1); @@ -353,7 +353,7 @@ void UARTDriver::_check_connection(void) return; } if (_select_check(_listen_fd)) { - _fd = accept(_listen_fd, NULL, NULL); + _fd = accept(_listen_fd, nullptr, nullptr); if (_fd != -1) { int one = 1; _connected = true; @@ -382,7 +382,7 @@ bool UARTDriver::_select_check(int fd) tv.tv_sec = 0; tv.tv_usec = 0; - if (select(fd+1, &fds, NULL, NULL, &tv) == 1) { + if (select(fd+1, &fds, nullptr, nullptr, &tv) == 1) { return true; } return false; diff --git a/libraries/AP_HAL_SITL/sitl_barometer.cpp b/libraries/AP_HAL_SITL/sitl_barometer.cpp index 914e69aba3..61eb3ce553 100644 --- a/libraries/AP_HAL_SITL/sitl_barometer.cpp +++ b/libraries/AP_HAL_SITL/sitl_barometer.cpp @@ -33,7 +33,7 @@ void SITL_State::_update_barometer(float altitude) float sim_alt = altitude; - if (_barometer == NULL) { + if (_barometer == nullptr) { // this sketch doesn't use a barometer return; } diff --git a/libraries/AP_HAL_SITL/sitl_compass.cpp b/libraries/AP_HAL_SITL/sitl_compass.cpp index 4b5fa3206a..3b031ed780 100644 --- a/libraries/AP_HAL_SITL/sitl_compass.cpp +++ b/libraries/AP_HAL_SITL/sitl_compass.cpp @@ -30,7 +30,7 @@ void SITL_State::_update_compass(float rollDeg, float pitchDeg, float yawDeg) { static uint32_t last_update; - if (_compass == NULL) { + if (_compass == nullptr) { // no compass in this sketch return; } diff --git a/libraries/AP_HAL_SITL/sitl_gps.cpp b/libraries/AP_HAL_SITL/sitl_gps.cpp index fe0c9aae24..76543d7c06 100644 --- a/libraries/AP_HAL_SITL/sitl_gps.cpp +++ b/libraries/AP_HAL_SITL/sitl_gps.cpp @@ -134,7 +134,7 @@ static void simulation_timeval(struct timeval *tv) static struct timeval first_tv; if (first_usec == 0) { first_usec = now; - gettimeofday(&first_tv, NULL); + gettimeofday(&first_tv, nullptr); } *tv = first_tv; tv->tv_sec += now / 1000000ULL; @@ -522,7 +522,7 @@ uint16_t SITL_State::_gps_nmea_checksum(const char *s) */ void SITL_State::_gps_nmea_printf(const char *fmt, ...) { - char *s = NULL; + char *s = nullptr; uint16_t csum; char trailer[6]; diff --git a/libraries/AP_HAL_SITL/sitl_ins.cpp b/libraries/AP_HAL_SITL/sitl_ins.cpp index 17dfc8b917..ef03101ad3 100644 --- a/libraries/AP_HAL_SITL/sitl_ins.cpp +++ b/libraries/AP_HAL_SITL/sitl_ins.cpp @@ -154,7 +154,7 @@ void SITL_State::_update_ins(float roll, float pitch, float yaw, // Relative double xAccel, double yAccel, double zAccel, // Local to plane float airspeed, float altitude) { - if (_ins == NULL) { + if (_ins == nullptr) { // no inertial sensor in this sketch return; } diff --git a/libraries/AP_HAL_SITL/system.cpp b/libraries/AP_HAL_SITL/system.cpp index 1e3aad5626..6ae2036205 100644 --- a/libraries/AP_HAL_SITL/system.cpp +++ b/libraries/AP_HAL_SITL/system.cpp @@ -18,7 +18,7 @@ static struct { void init() { - gettimeofday(&state.start_time, NULL); + gettimeofday(&state.start_time, nullptr); } void panic(const char *errormsg, ...) @@ -52,7 +52,7 @@ uint64_t micros64() } struct timeval tp; - gettimeofday(&tp, NULL); + gettimeofday(&tp, nullptr); uint64_t ret = 1.0e6 * ((tp.tv_sec + (tp.tv_usec * 1.0e-6)) - (state.start_time.tv_sec + (state.start_time.tv_usec * 1.0e-6))); @@ -68,7 +68,7 @@ uint64_t millis64() } struct timeval tp; - gettimeofday(&tp, NULL); + gettimeofday(&tp, nullptr); uint64_t ret = 1.0e3*((tp.tv_sec + (tp.tv_usec*1.0e-6)) - (state.start_time.tv_sec + (state.start_time.tv_usec*1.0e-6))); diff --git a/libraries/AP_HAL_VRBRAIN/AnalogIn.cpp b/libraries/AP_HAL_VRBRAIN/AnalogIn.cpp index 5db8475f12..2b8a32a6d2 100644 --- a/libraries/AP_HAL_VRBRAIN/AnalogIn.cpp +++ b/libraries/AP_HAL_VRBRAIN/AnalogIn.cpp @@ -248,7 +248,7 @@ void VRBRAINAnalogIn::_timer_tick(void) struct adc_msg_s buf_adc[VRBRAIN_ANALOG_MAX_CHANNELS]; // cope with initial setup of stop pin - if (_channels[_current_stop_pin_i] == NULL || + if (_channels[_current_stop_pin_i] == nullptr || _channels[_current_stop_pin_i]->_stop_pin == -1) { next_stop_pin(); } @@ -263,7 +263,7 @@ void VRBRAINAnalogIn::_timer_tick(void) (unsigned)buf_adc[i].am_data); for (uint8_t j=0; j_pin) { + if (c != nullptr && buf_adc[i].am_channel == c->_pin) { // add a value if either there is no stop pin, or // the stop pin has been settling for enough time if (c->_stop_pin == -1 || @@ -284,13 +284,13 @@ void VRBRAINAnalogIn::_timer_tick(void) AP_HAL::AnalogSource* VRBRAINAnalogIn::channel(int16_t pin) { for (uint8_t j=0; jprintln("Out of analog channels"); - return NULL; + return nullptr; } #endif // CONFIG_HAL_BOARD diff --git a/libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp b/libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp index 6a73271a26..86c7fdeb2f 100644 --- a/libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp +++ b/libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp @@ -126,7 +126,7 @@ HAL_VRBRAIN::HAL_VRBRAIN() : &rcoutDriver, /* rcoutput */ &schedulerInstance, /* scheduler */ &utilInstance, /* util */ - NULL) /* no onboard optical flow */ + nullptr) /* no onboard optical flow */ {} bool _vrbrain_thread_should_exit = false; /**< Daemon exit flag */ @@ -205,7 +205,7 @@ static int main_loop(int argc, char **argv) will only ever be called if a loop() call runs for more than 0.1 second */ - hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)loop_overtime, NULL); + hrt_call_after(&loop_overtime_call, 100000, (hrt_callout)loop_overtime, nullptr); g_callbacks->loop(); @@ -283,7 +283,7 @@ void HAL_VRBRAIN::run(int argc, char * const argv[], Callbacks* callbacks) const APM_MAIN_PRIORITY, APM_MAIN_THREAD_STACK_SIZE, main_loop, - NULL); + nullptr); exit(0); } diff --git a/libraries/AP_HAL_VRBRAIN/NSHShellStream.cpp b/libraries/AP_HAL_VRBRAIN/NSHShellStream.cpp index cf040303ac..01d1f8a4ca 100644 --- a/libraries/AP_HAL_VRBRAIN/NSHShellStream.cpp +++ b/libraries/AP_HAL_VRBRAIN/NSHShellStream.cpp @@ -31,7 +31,7 @@ void NSHShellStream::shell_thread(void *arg) dup2(nsh->child.out, 1); dup2(nsh->child.out, 2); - nsh_consolemain(0, NULL); + nsh_consolemain(0, nullptr); nsh->shell_stdin = -1; nsh->shell_stdout = -1; diff --git a/libraries/AP_HAL_VRBRAIN/RCInput.cpp b/libraries/AP_HAL_VRBRAIN/RCInput.cpp index 4c78ead501..56535b8b27 100644 --- a/libraries/AP_HAL_VRBRAIN/RCInput.cpp +++ b/libraries/AP_HAL_VRBRAIN/RCInput.cpp @@ -20,7 +20,7 @@ void VRBRAINRCInput::init() AP_HAL::panic("Unable to subscribe to input_rc"); } clear_overrides(); - pthread_mutex_init(&rcin_mutex, NULL); + pthread_mutex_init(&rcin_mutex, nullptr); } bool VRBRAINRCInput::new_input() diff --git a/libraries/AP_HAL_VRBRAIN/RCOutput.cpp b/libraries/AP_HAL_VRBRAIN/RCOutput.cpp index 0ca0eef3c9..0773e97f02 100644 --- a/libraries/AP_HAL_VRBRAIN/RCOutput.cpp +++ b/libraries/AP_HAL_VRBRAIN/RCOutput.cpp @@ -67,10 +67,10 @@ void VRBRAINRCOutput::init() } // publish actuator vaules on demand - _actuator_direct_pub = NULL; + _actuator_direct_pub = nullptr; // and armed state - _actuator_armed_pub = NULL; + _actuator_armed_pub = nullptr; } @@ -390,7 +390,7 @@ void VRBRAINRCOutput::_arm_actuators(bool arm) _armed.lockdown = false; _armed.force_failsafe = false; - if (_actuator_armed_pub == NULL) { + if (_actuator_armed_pub == nullptr) { _actuator_armed_pub = orb_advertise(ORB_ID(actuator_armed), &_armed); } else { orb_publish(ORB_ID(actuator_armed), _actuator_armed_pub, &_armed); @@ -432,7 +432,7 @@ void VRBRAINRCOutput::_publish_actuators(void) actuators.values[i] = actuators.values[i]*2 - 1; } - if (_actuator_direct_pub == NULL) { + if (_actuator_direct_pub == nullptr) { _actuator_direct_pub = orb_advertise(ORB_ID(actuator_direct), &actuators); } else { orb_publish(ORB_ID(actuator_direct), _actuator_direct_pub, &actuators); diff --git a/libraries/AP_HAL_VRBRAIN/RCOutput.h b/libraries/AP_HAL_VRBRAIN/RCOutput.h index 8a4eb3165b..648127f0d4 100644 --- a/libraries/AP_HAL_VRBRAIN/RCOutput.h +++ b/libraries/AP_HAL_VRBRAIN/RCOutput.h @@ -58,8 +58,8 @@ private: } _outputs[ORB_MULTI_MAX_INSTANCES] {}; actuator_armed_s _armed; - orb_advert_t _actuator_direct_pub = NULL; - orb_advert_t _actuator_armed_pub = NULL; + orb_advert_t _actuator_direct_pub = nullptr; + orb_advert_t _actuator_armed_pub = nullptr; uint16_t _esc_pwm_min = 0; uint16_t _esc_pwm_max = 0; diff --git a/libraries/AP_HAL_VRBRAIN/Scheduler.cpp b/libraries/AP_HAL_VRBRAIN/Scheduler.cpp index 3d01f2df87..c86201a670 100644 --- a/libraries/AP_HAL_VRBRAIN/Scheduler.cpp +++ b/libraries/AP_HAL_VRBRAIN/Scheduler.cpp @@ -133,7 +133,7 @@ void VRBRAINScheduler::delay_microseconds_boost(uint16_t usec) sem_init(&wait_semaphore, 0, 0); hrt_call_after(&wait_call, usec, (hrt_callout)sem_post_boost, &wait_semaphore); sem_wait(&wait_semaphore); - hrt_call_after(&wait_call, APM_MAIN_PRIORITY_BOOST_USEC, (hrt_callout)set_normal_priority, NULL); + hrt_call_after(&wait_call, APM_MAIN_PRIORITY_BOOST_USEC, (hrt_callout)set_normal_priority, nullptr); } void VRBRAINScheduler::delay(uint16_t ms) @@ -249,7 +249,7 @@ void VRBRAINScheduler::_run_timers(bool called_from_timer_thread) } // and the failsafe, if one is setup - if (_failsafe != NULL) { + if (_failsafe != nullptr) { _failsafe(); } @@ -267,7 +267,7 @@ void *VRBRAINScheduler::_timer_thread(void *arg) uint32_t last_ran_overtime = 0; while (!sched->_hal_initialized) { - poll(NULL, 0, 1); + poll(nullptr, 0, 1); } while (!_vrbrain_thread_should_exit) { sched->delay_microseconds_semaphore(1000); @@ -291,7 +291,7 @@ void *VRBRAINScheduler::_timer_thread(void *arg) #endif } } - return NULL; + return nullptr; } void VRBRAINScheduler::_run_io(void) @@ -318,7 +318,7 @@ void *VRBRAINScheduler::_uart_thread(void *arg) VRBRAINScheduler *sched = (VRBRAINScheduler *)arg; while (!sched->_hal_initialized) { - poll(NULL, 0, 1); + poll(nullptr, 0, 1); } while (!_vrbrain_thread_should_exit) { sched->delay_microseconds_semaphore(1000); @@ -331,7 +331,7 @@ void *VRBRAINScheduler::_uart_thread(void *arg) ((VRBRAINUARTDriver *)hal.uartE)->_timer_tick(); ((VRBRAINUARTDriver *)hal.uartF)->_timer_tick(); } - return NULL; + return nullptr; } void *VRBRAINScheduler::_io_thread(void *arg) @@ -339,17 +339,17 @@ void *VRBRAINScheduler::_io_thread(void *arg) VRBRAINScheduler *sched = (VRBRAINScheduler *)arg; while (!sched->_hal_initialized) { - poll(NULL, 0, 1); + poll(nullptr, 0, 1); } while (!_vrbrain_thread_should_exit) { - poll(NULL, 0, 1); + poll(nullptr, 0, 1); // run registered IO processes perf_begin(sched->_perf_io_timers); sched->_run_io(); perf_end(sched->_perf_io_timers); } - return NULL; + return nullptr; } void *VRBRAINScheduler::_storage_thread(void *arg) @@ -357,17 +357,17 @@ void *VRBRAINScheduler::_storage_thread(void *arg) VRBRAINScheduler *sched = (VRBRAINScheduler *)arg; while (!sched->_hal_initialized) { - poll(NULL, 0, 1); + poll(nullptr, 0, 1); } while (!_vrbrain_thread_should_exit) { - poll(NULL, 0, 10); + poll(nullptr, 0, 10); // process any pending storage writes perf_begin(sched->_perf_storage_timer); ((VRBRAINStorage *)hal.storage)->_timer_tick(); perf_end(sched->_perf_storage_timer); } - return NULL; + return nullptr; } bool VRBRAINScheduler::in_timerprocess() diff --git a/libraries/AP_HAL_VRBRAIN/Semaphores.h b/libraries/AP_HAL_VRBRAIN/Semaphores.h index 8b64f4b4d8..91c0f686fd 100644 --- a/libraries/AP_HAL_VRBRAIN/Semaphores.h +++ b/libraries/AP_HAL_VRBRAIN/Semaphores.h @@ -9,7 +9,7 @@ class VRBRAIN::Semaphore : public AP_HAL::Semaphore { public: Semaphore() { - pthread_mutex_init(&_lock, NULL); + pthread_mutex_init(&_lock, nullptr); } bool give(); bool take(uint32_t timeout_ms); diff --git a/libraries/AP_HAL_VRBRAIN/Util.cpp b/libraries/AP_HAL_VRBRAIN/Util.cpp index fbf7611e9f..6305d16349 100644 --- a/libraries/AP_HAL_VRBRAIN/Util.cpp +++ b/libraries/AP_HAL_VRBRAIN/Util.cpp @@ -61,7 +61,7 @@ bool VRBRAINUtil::run_debug_shell(AP_HAL::BetterStream *stream) dup2(fd, 1); dup2(fd, 2); - nsh_consolemain(0, NULL); + nsh_consolemain(0, nullptr); // this shouldn't happen hal.console->printf("shell exited\n"); @@ -158,7 +158,7 @@ VRBRAINUtil::perf_counter_t VRBRAINUtil::perf_alloc(VRBRAINUtil::perf_counter_ty vrbrain_t = ::PC_INTERVAL; break; default: - return NULL; + return nullptr; } return (perf_counter_t)::perf_alloc(vrbrain_t, name); } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index f64f34c29b..f5bdf3c445 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -399,7 +399,7 @@ AP_InertialSensor::AP_InertialSensor() : _calibrating(false), _log_raw_data(false), _backends_detected(false), - _dataflash(NULL), + _dataflash(nullptr), _accel_cal_requires_reboot(false), _startup_error_counts_set(false), _startup_ms(0) @@ -410,7 +410,7 @@ AP_InertialSensor::AP_InertialSensor() : _s_instance = this; AP_Param::setup_object_defaults(this, var_info); for (uint8_t i=0; iget_auxiliary_bus(); } @@ -1399,10 +1399,10 @@ bool AP_InertialSensor::is_still() void AP_InertialSensor::acal_init() { // NOTE: these objects are never deallocated because the pre-arm checks force a reboot - if (_acal == NULL) { + if (_acal == nullptr) { _acal = new AP_AccelCal; } - if (_accel_calibrator == NULL) { + if (_accel_calibrator == nullptr) { _accel_calibrator = new AccelCalibrator[INS_MAX_INSTANCES]; } } @@ -1410,7 +1410,7 @@ void AP_InertialSensor::acal_init() // update accel calibrator void AP_InertialSensor::acal_update() { - if(_acal == NULL) { + if(_acal == nullptr) { return; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index 3083973c0f..7b7934c99f 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -427,7 +427,7 @@ private: void _acal_event_failure(); // Returns AccelCalibrator objects pointer for specified acceleromter - AccelCalibrator* _acal_get_calibrator(uint8_t i) { return i_init_sensor()) { delete sensor; - return NULL; + return nullptr; } return sensor; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp index 515b7b8786..a5f4e4d424 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp @@ -27,12 +27,12 @@ AP_InertialSensor_PX4::AP_InertialSensor_PX4(AP_InertialSensor &imu) : AP_InertialSensor_Backend *AP_InertialSensor_PX4::detect(AP_InertialSensor &_imu) { AP_InertialSensor_PX4 *sensor = new AP_InertialSensor_PX4(_imu); - if (sensor == NULL) { - return NULL; + if (sensor == nullptr) { + return nullptr; } if (!sensor->_init_sensor()) { delete sensor; - return NULL; + return nullptr; } return sensor; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_QURT.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_QURT.cpp index 8757f2023f..54bf2af4d3 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_QURT.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_QURT.cpp @@ -18,12 +18,12 @@ AP_InertialSensor_QURT::AP_InertialSensor_QURT(AP_InertialSensor &imu) : AP_InertialSensor_Backend *AP_InertialSensor_QURT::detect(AP_InertialSensor &_imu) { AP_InertialSensor_QURT *sensor = new AP_InertialSensor_QURT(_imu); - if (sensor == NULL) { - return NULL; + if (sensor == nullptr) { + return nullptr; } if (!sensor->init_sensor()) { delete sensor; - return NULL; + return nullptr; } return sensor; } @@ -50,7 +50,7 @@ extern "C" { static void *mpu_data_ready_trampoline(void *ctx) { ((AP_InertialSensor_QURT *)ctx)->data_ready(); - return NULL; + return nullptr; } void AP_InertialSensor_QURT::init_mpu9250(void) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp index 7b18ae781c..b3032509fa 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp @@ -17,12 +17,12 @@ AP_InertialSensor_SITL::AP_InertialSensor_SITL(AP_InertialSensor &imu) : AP_InertialSensor_Backend *AP_InertialSensor_SITL::detect(AP_InertialSensor &_imu) { AP_InertialSensor_SITL *sensor = new AP_InertialSensor_SITL(_imu); - if (sensor == NULL) { - return NULL; + if (sensor == nullptr) { + return nullptr; } if (!sensor->init_sensor()) { delete sensor; - return NULL; + return nullptr; } return sensor; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp index 80d0fa3d16..2a666070ce 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp @@ -28,12 +28,12 @@ bool AP_InertialSensor_UserInteract_MAVLink::blocking_read(void) while (AP_HAL::millis() - start_ms < 30000U) { hal.scheduler->delay(10); if (_got_ack) { - _gcs->set_snoop(NULL); + _gcs->set_snoop(nullptr); return true; } } hal.console->println("Timed out waiting for user response"); - _gcs->set_snoop(NULL); + _gcs->set_snoop(nullptr); return false; } diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_qflight.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_qflight.cpp index 200a8f9f7b..19ebacab43 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_qflight.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_qflight.cpp @@ -19,12 +19,12 @@ AP_InertialSensor_QFLIGHT::AP_InertialSensor_QFLIGHT(AP_InertialSensor &imu) : AP_InertialSensor_Backend *AP_InertialSensor_QFLIGHT::detect(AP_InertialSensor &_imu) { AP_InertialSensor_QFLIGHT *sensor = new AP_InertialSensor_QFLIGHT(_imu); - if (sensor == NULL) { - return NULL; + if (sensor == nullptr) { + return nullptr; } if (!sensor->init_sensor()) { delete sensor; - return NULL; + return nullptr; } return sensor; } diff --git a/libraries/AP_Math/matrix3.cpp b/libraries/AP_Math/matrix3.cpp index e930365cbc..df3f7442b2 100644 --- a/libraries/AP_Math/matrix3.cpp +++ b/libraries/AP_Math/matrix3.cpp @@ -48,13 +48,13 @@ void Matrix3::from_euler(float roll, float pitch, float yaw) template void Matrix3::to_euler(float *roll, float *pitch, float *yaw) const { - if (pitch != NULL) { + if (pitch != nullptr) { *pitch = -safe_asin(c.x); } - if (roll != NULL) { + if (roll != nullptr) { *roll = atan2f(c.y, c.z); } - if (yaw != NULL) { + if (yaw != nullptr) { *yaw = atan2f(b.x, a.x); } } diff --git a/libraries/AP_Menu/AP_Menu.cpp b/libraries/AP_Menu/AP_Menu.cpp index 2d8eced540..5ec969b77b 100644 --- a/libraries/AP_Menu/AP_Menu.cpp +++ b/libraries/AP_Menu/AP_Menu.cpp @@ -26,10 +26,10 @@ Menu::Menu(const char *prompt, const Menu::command *commands, uint8_t entries, p _commandline_max(MENU_COMMANDLINE_MAX), _args_max(MENU_ARGS_MAX) { - // the buffers are initially NULL, then they are allocated on + // the buffers are initially nullptr, then they are allocated on // first use - _inbuf = NULL; - _argv = NULL; + _inbuf = nullptr; + _argv = nullptr; } /** @@ -89,26 +89,26 @@ Menu::_run_command(bool prompt_on_enter) int8_t ret; uint8_t i; uint8_t argc; - char *s = NULL; + char *s = nullptr; _input_len = 0; // split the input line into tokens argc = 0; - s = NULL; + s = nullptr; _argv[argc++].str = strtok_r(_inbuf, " ", &s); // XXX should an empty line by itself back out of the current menu? while (argc <= _args_max) { - _argv[argc].str = strtok_r(NULL, " ", &s); - if (_argv[argc].str == NULL || '\0' == _argv[argc].str[0]) + _argv[argc].str = strtok_r(nullptr, " ", &s); + if (_argv[argc].str == nullptr || '\0' == _argv[argc].str[0]) break; _argv[argc].i = atol(_argv[argc].str); _argv[argc].f = atof(_argv[argc].str); // calls strtod, > 700B ! argc++; } - if (_argv[0].str == NULL) { + if (_argv[0].str == nullptr) { // we got a blank line, re-display the prompt if (prompt_on_enter) { _display_prompt(); @@ -163,7 +163,7 @@ Menu::_run_command(bool prompt_on_enter) void Menu::run(void) { - if (_port == NULL) { + if (_port == nullptr) { // default to main serial port _port = hal.console; } @@ -203,7 +203,7 @@ Menu::run(void) bool Menu::check_input(void) { - if (_port == NULL) { + if (_port == nullptr) { // default to main serial port _port = hal.console; } @@ -243,13 +243,13 @@ Menu::_call(uint8_t n, uint8_t argc) void Menu::set_limits(uint8_t commandline_max, uint8_t args_max) { - if (_inbuf != NULL) { + if (_inbuf != nullptr) { delete[] _inbuf; - _inbuf = NULL; + _inbuf = nullptr; } - if (_argv != NULL) { + if (_argv != nullptr) { delete[] _argv; - _argv = NULL; + _argv = nullptr; } // remember limits, the buffers will be allocated by allocate_buffers() _commandline_max = commandline_max; @@ -259,12 +259,12 @@ Menu::set_limits(uint8_t commandline_max, uint8_t args_max) void Menu::_allocate_buffers(void) { - /* only allocate if the buffers are NULL */ - if (_inbuf == NULL) { + /* only allocate if the buffers are nullptr */ + if (_inbuf == nullptr) { _inbuf = new char[_commandline_max]; memset(_inbuf, 0, _commandline_max); } - if (_argv == NULL) { + if (_argv == nullptr) { _argv = new arg[_args_max+1]; memset(_argv, 0, (_args_max+1) * sizeof(_argv[0])); } diff --git a/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp b/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp index dea026e4c3..595a9450cf 100644 --- a/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp +++ b/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp @@ -25,7 +25,7 @@ void setup(void) baro.init(); ahrs.init(); - gps.init(NULL, serial_manager); + gps.init(nullptr, serial_manager); } void loop(void) diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 33dc2377b5..6d37ade993 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -403,7 +403,7 @@ AP_Mount::AP_Mount(const AP_AHRS_TYPE &ahrs, const struct Location ¤t_loc) // initialise backend pointers and mode for (uint8_t i=0; iinit(serial_manager); if (!primary_set) { _primary = instance; @@ -480,7 +480,7 @@ void AP_Mount::update() { // update each instance for (uint8_t instance=0; instanceupdate(); } } @@ -491,7 +491,7 @@ void AP_Mount::update_fast() { // update each instance for (uint8_t instance=0; instanceupdate_fast(); } } @@ -510,7 +510,7 @@ AP_Mount::MountType AP_Mount::get_mount_type(uint8_t instance) const // has_pan_control - returns true if the mount has yaw control (required for copters) bool AP_Mount::has_pan_control(uint8_t instance) const { - if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == NULL) { + if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == nullptr) { return false; } @@ -540,7 +540,7 @@ void AP_Mount::set_mode_to_default(uint8_t instance) void AP_Mount::set_mode(uint8_t instance, enum MAV_MOUNT_MODE mode) { // sanity check instance - if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == NULL) { + if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == nullptr) { return; } @@ -551,7 +551,7 @@ void AP_Mount::set_mode(uint8_t instance, enum MAV_MOUNT_MODE mode) // set_angle_targets - sets angle targets in degrees void AP_Mount::set_angle_targets(uint8_t instance, float roll, float tilt, float pan) { - if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == NULL) { + if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == nullptr) { return; } @@ -563,7 +563,7 @@ void AP_Mount::set_angle_targets(uint8_t instance, float roll, float tilt, float /// triggered by a MavLink packet. void AP_Mount::configure_msg(uint8_t instance, mavlink_message_t* msg) { - if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == NULL) { + if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == nullptr) { return; } @@ -575,7 +575,7 @@ void AP_Mount::configure_msg(uint8_t instance, mavlink_message_t* msg) /// triggered by a MavLink packet. void AP_Mount::control_msg(uint8_t instance, mavlink_message_t *msg) { - if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == NULL) { + if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == nullptr) { return; } @@ -585,7 +585,7 @@ void AP_Mount::control_msg(uint8_t instance, mavlink_message_t *msg) void AP_Mount::control(uint8_t instance, int32_t pitch_or_lat, int32_t roll_or_lon, int32_t yaw_or_alt, enum MAV_MOUNT_MODE mount_mode) { - if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == NULL) { + if (instance >= AP_MOUNT_MAX_INSTANCES || _backends[instance] == nullptr) { return; } @@ -598,7 +598,7 @@ void AP_Mount::status_msg(mavlink_channel_t chan) { // call status_msg for each instance for (uint8_t instance=0; instancestatus_msg(chan); } } @@ -608,7 +608,7 @@ void AP_Mount::status_msg(mavlink_channel_t chan) void AP_Mount::set_roi_target(uint8_t instance, const struct Location &target_loc) { // call instance's set_roi_cmd - if (instance < AP_MOUNT_MAX_INSTANCES && _backends[instance] != NULL) { + if (instance < AP_MOUNT_MAX_INSTANCES && _backends[instance] != nullptr) { _backends[instance]->set_roi_target(target_loc); } } @@ -617,7 +617,7 @@ void AP_Mount::set_roi_target(uint8_t instance, const struct Location &target_lo void AP_Mount::handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *msg) { for (uint8_t instance=0; instancehandle_gimbal_report(chan, msg); } } @@ -627,7 +627,7 @@ void AP_Mount::handle_gimbal_report(mavlink_channel_t chan, mavlink_message_t *m void AP_Mount::handle_param_value(mavlink_message_t *msg) { for (uint8_t instance=0; instancehandle_param_value(msg); } } @@ -637,7 +637,7 @@ void AP_Mount::handle_param_value(mavlink_message_t *msg) void AP_Mount::send_gimbal_report(mavlink_channel_t chan) { for (uint8_t instance=0; instancesend_gimbal_report(chan); } } diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.h b/libraries/AP_Mount/AP_Mount_Alexmos.h index 3d5a0b0333..c3a575e9ca 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.h +++ b/libraries/AP_Mount/AP_Mount_Alexmos.h @@ -68,7 +68,7 @@ public: //constructor AP_Mount_Alexmos(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance): AP_Mount_Backend(frontend, state, instance), - _port(NULL), + _port(nullptr), _initialised(false), _board_version(0), _current_firmware_version(0.0f), diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp index 8e4d0ca618..0a97660c58 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp @@ -8,7 +8,7 @@ extern const AP_HAL::HAL& hal; AP_Mount_SToRM32_serial::AP_Mount_SToRM32_serial(AP_Mount &frontend, AP_Mount::mount_state &state, uint8_t instance) : AP_Mount_Backend(frontend, state, instance), - _port(NULL), + _port(nullptr), _initialised(false), _last_send(0), _reply_length(0), diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp index 21e962d2fa..bfa7dabb21 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp @@ -119,7 +119,7 @@ void AP_Mount_SoloGimbal::handle_gimbal_report(mavlink_channel_t chan, mavlink_m _gimbal.update_target(_angle_ef_target_rad); _gimbal.receive_feedback(chan,msg); - if(!_params_saved && _frontend._dataflash != NULL && _frontend._dataflash->logging_started()) { + if(!_params_saved && _frontend._dataflash != nullptr && _frontend._dataflash->logging_started()) { _gimbal.fetch_params(); //last parameter save might not be stored in dataflash so retry _params_saved = true; } diff --git a/libraries/AP_Mount/SoloGimbal.cpp b/libraries/AP_Mount/SoloGimbal.cpp index 1890f2c3e4..2dd1f295eb 100644 --- a/libraries/AP_Mount/SoloGimbal.cpp +++ b/libraries/AP_Mount/SoloGimbal.cpp @@ -373,7 +373,7 @@ void SoloGimbal::update_target(Vector3f newTarget) void SoloGimbal::write_logs(DataFlash_Class* dataflash) { - if (dataflash == NULL) return; + if (dataflash == nullptr) return; uint32_t tstamp = AP_HAL::millis(); Vector3f eulerEst; @@ -429,7 +429,7 @@ AccelCalibrator* SoloGimbal::_acal_get_calibrator(uint8_t instance) if(instance==0 && (present() || _calibrator.get_status() == ACCEL_CAL_SUCCESS)) { return &_calibrator; } else { - return NULL; + return nullptr; } } diff --git a/libraries/AP_Mount/SoloGimbal_Parameters.cpp b/libraries/AP_Mount/SoloGimbal_Parameters.cpp index ecb8bff574..5c10919353 100644 --- a/libraries/AP_Mount/SoloGimbal_Parameters.cpp +++ b/libraries/AP_Mount/SoloGimbal_Parameters.cpp @@ -171,7 +171,7 @@ void SoloGimbal_Parameters::handle_param_value(DataFlash_Class *dataflash, mavli mavlink_param_value_t packet; mavlink_msg_param_value_decode(msg, &packet); - if (dataflash != NULL) { + if (dataflash != nullptr) { dataflash->Log_Write_Parameter(packet.param_id, packet.param_value); } diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Buffer.h b/libraries/AP_NavEKF2/AP_NavEKF2_Buffer.h index 7de44cdac3..4310281f05 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Buffer.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Buffer.h @@ -15,7 +15,7 @@ public: bool init(uint32_t size) { buffer = new element_t[size]; - if(buffer == NULL) + if(buffer == nullptr) { return false; } @@ -126,7 +126,7 @@ public: bool init(uint32_t size) { buffer = new element_t[size]; - if(buffer == NULL) + if(buffer == nullptr) { return false; } @@ -185,4 +185,4 @@ public: } private: uint8_t _size,_oldest,_youngest; -}; \ No newline at end of file +}; diff --git a/libraries/AP_OpticalFlow/OpticalFlow.cpp b/libraries/AP_OpticalFlow/OpticalFlow.cpp index 303fe4fe98..a0040d86e8 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/OpticalFlow.cpp @@ -87,7 +87,7 @@ void OpticalFlow::init(void) #endif } - if (backend != NULL) { + if (backend != nullptr) { backend->init(); } else { _enabled = 0; @@ -96,7 +96,7 @@ void OpticalFlow::init(void) void OpticalFlow::update(void) { - if (backend != NULL) { + if (backend != nullptr) { backend->update(); } // only healthy if the data is less than 0.5s old diff --git a/libraries/AP_OpticalFlow/OpticalFlow.h b/libraries/AP_OpticalFlow/OpticalFlow.h index 4caf99482e..518de1f38b 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.h +++ b/libraries/AP_OpticalFlow/OpticalFlow.h @@ -40,7 +40,7 @@ public: bool enabled() const { return _enabled; } // healthy - return true if the sensor is healthy - bool healthy() const { return backend != NULL && _flags.healthy; } + bool healthy() const { return backend != nullptr && _flags.healthy; } // read latest values from sensor and fill in x,y and totals. void update(void); diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 2cd3bbe1f7..4205e2a0e6 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -65,7 +65,7 @@ uint16_t AP_Param::_parameter_count; // storage and naming information about all types that can be saved const AP_Param::Info *AP_Param::_var_info; -struct AP_Param::param_override *AP_Param::param_overrides = NULL; +struct AP_Param::param_override *AP_Param::param_overrides = nullptr; uint16_t AP_Param::num_param_overrides = 0; // storage object @@ -155,7 +155,7 @@ bool AP_Param::check_group_info(const struct AP_Param::GroupInfo * group_info, Debug("double group nesting in %s", group_info[i].name); return false; } - if (ginfo == NULL || + if (ginfo == nullptr || !check_group_info(ginfo, total_size, group_shift + _group_level_shift, prefix_length + strlen(group_info[i].name))) { return false; } @@ -207,7 +207,7 @@ bool AP_Param::check_var_info(void) return false; } const struct GroupInfo *group_info = _var_info[i].group_info; - if (group_info == NULL || + if (group_info == nullptr || !check_group_info(group_info, &total_size, 0, strlen(_var_info[i].name))) { return false; } @@ -259,7 +259,7 @@ bool AP_Param::setup(void) // check if AP_Param has been initialised bool AP_Param::initialised(void) { - return _var_info != NULL; + return _var_info != nullptr; } /* @@ -324,7 +324,7 @@ const struct AP_Param::Info *AP_Param::find_by_header_group(struct Param_header if (group_shift + _group_level_shift >= _group_bits) { // too deeply nested - this should have been caught by // setup() ! - return NULL; + return nullptr; } const struct GroupInfo *ginfo = group_info[i].group_info; ptrdiff_t new_offset = group_offset; @@ -336,7 +336,7 @@ const struct AP_Param::Info *AP_Param::find_by_header_group(struct Param_header const struct AP_Param::Info *ret = find_by_header_group(phdr, ptr, vindex, ginfo, group_id(group_info, group_base, i, group_shift), group_shift + _group_level_shift, new_offset); - if (ret != NULL) { + if (ret != nullptr) { return ret; } continue; @@ -351,7 +351,7 @@ const struct AP_Param::Info *AP_Param::find_by_header_group(struct Param_header return &_var_info[vindex]; } } - return NULL; + return nullptr; } // find the info structure given a header @@ -374,13 +374,13 @@ const struct AP_Param::Info *AP_Param::find_by_header(struct Param_header phdr, // found it ptrdiff_t base; if (!get_base(_var_info[i], base)) { - return NULL; + return nullptr; } *ptr = (void*)base; return &_var_info[i]; } } - return NULL; + return nullptr; } // find the info structure for a variable in a group @@ -396,7 +396,7 @@ const struct AP_Param::Info *AP_Param::find_var_info_group(const struct GroupInf { ptrdiff_t base; if (!get_base(_var_info[vindex], base)) { - return NULL; + return nullptr; } uint8_t type; for (uint8_t i=0; @@ -409,7 +409,7 @@ const struct AP_Param::Info *AP_Param::find_var_info_group(const struct GroupInf if (group_shift + _group_level_shift >= _group_bits) { // too deeply nested - this should have been caught by // setup() ! - return NULL; + return nullptr; } const struct AP_Param::Info *info; ptrdiff_t new_offset = group_offset; @@ -417,7 +417,7 @@ const struct AP_Param::Info *AP_Param::find_var_info_group(const struct GroupInf continue; } if (group_nesting.level >= group_nesting.numlevels) { - return NULL; + return nullptr; } group_nesting.group_ret[group_nesting.level++] = &group_info[i]; info = find_var_info_group(ginfo, vindex, @@ -428,7 +428,7 @@ const struct AP_Param::Info *AP_Param::find_var_info_group(const struct GroupInf group_ret, group_nesting, idx); - if (info != NULL) { + if (info != nullptr) { return info; } group_nesting.level--; @@ -448,7 +448,7 @@ const struct AP_Param::Info *AP_Param::find_var_info_group(const struct GroupInf return &_var_info[vindex]; } } - return NULL; + return nullptr; } // find the info structure for a variable @@ -457,7 +457,7 @@ const struct AP_Param::Info *AP_Param::find_var_info(uint32_t * struct GroupNesting &group_nesting, uint8_t * idx) const { - group_ret = NULL; + group_ret = nullptr; for (uint16_t i=0; i<_num_vars; i++) { uint8_t type = _var_info[i].type; @@ -469,7 +469,7 @@ const struct AP_Param::Info *AP_Param::find_var_info(uint32_t * const struct GroupInfo *group_info = _var_info[i].group_info; const struct AP_Param::Info *info; info = find_var_info_group(group_info, i, 0, 0, 0, group_element, group_ret, group_nesting, idx); - if (info != NULL) { + if (info != nullptr) { return info; } } else if (base == (ptrdiff_t) this) { @@ -486,7 +486,7 @@ const struct AP_Param::Info *AP_Param::find_var_info(uint32_t * return &_var_info[i]; } } - return NULL; + return nullptr; } @@ -501,15 +501,15 @@ const struct AP_Param::Info *AP_Param::find_var_info_token(const ParamToken &tok uint8_t type = _var_info[i].type; ptrdiff_t base; if (!get_base(_var_info[i], base)) { - return NULL; + return nullptr; } - group_ret = NULL; + group_ret = nullptr; if (type == AP_PARAM_GROUP) { const struct GroupInfo *group_info = _var_info[i].group_info; const struct AP_Param::Info *info; info = find_var_info_group(group_info, i, 0, 0, 0, group_element, group_ret, group_nesting, idx); - if (info != NULL) { + if (info != nullptr) { return info; } } else if (base == (ptrdiff_t) this) { @@ -525,7 +525,7 @@ const struct AP_Param::Info *AP_Param::find_var_info_token(const ParamToken &tok *group_element = 0; return &_var_info[i]; } - return NULL; + return nullptr; } // return the storage size for a AP_PARAM_* type @@ -641,7 +641,7 @@ void AP_Param::copy_name_token(const ParamToken &token, char *buffer, size_t buf struct GroupNesting group_nesting {}; uint8_t idx; const struct AP_Param::Info *info = find_var_info_token(token, &group_element, ginfo, group_nesting, &idx); - if (info == NULL) { + if (info == nullptr) { *buffer = 0; Debug("no info found"); return; @@ -661,7 +661,7 @@ void AP_Param::copy_name_info(const struct AP_Param::Info *info, strncpy(&buffer[len], group_nesting.group_ret[i]->name, buffer_size-len); } } - if (ginfo != NULL) { + if (ginfo != nullptr) { uint8_t len = strnlen(buffer, buffer_size); if (len < buffer_size) { strncpy(&buffer[len], ginfo->name, buffer_size-len); @@ -696,7 +696,7 @@ AP_Param::find_group(const char *name, uint16_t vindex, ptrdiff_t group_offset, } AP_Param *ap = find_group(name+strlen(group_info[i].name), vindex, new_offset, ginfo, ptype); - if (ap != NULL) { + if (ap != nullptr) { return ap; } } else if (strcasecmp(name, group_info[i].name) == 0) { @@ -731,7 +731,7 @@ AP_Param::find_group(const char *name, uint16_t vindex, ptrdiff_t group_offset, } } } - return NULL; + return nullptr; } @@ -749,7 +749,7 @@ AP_Param::find(const char *name, enum ap_var_type *ptype) } const struct GroupInfo *group_info = _var_info[i].group_info; AP_Param *ap = find_group(name + len, i, 0, group_info, ptype); - if (ap != NULL) { + if (ap != nullptr) { return ap; } // we continue looking as we want to allow top level @@ -759,12 +759,12 @@ AP_Param::find(const char *name, enum ap_var_type *ptype) *ptype = (enum ap_var_type)type; ptrdiff_t base; if (!get_base(_var_info[i], base)) { - return NULL; + return nullptr; } return (AP_Param *)base; } } - return NULL; + return nullptr; } /* @@ -775,18 +775,18 @@ AP_Param::find_def_value_ptr(const char *name) { enum ap_var_type ptype; AP_Param *vp = find(name, &ptype); - if (vp == NULL) { - return NULL; + if (vp == nullptr) { + return nullptr; } uint32_t group_element; const struct GroupInfo *ginfo; struct GroupNesting group_nesting {}; uint8_t gidx; const struct AP_Param::Info *info = vp->find_var_info(&group_element, ginfo, group_nesting, &gidx); - if (info == NULL) { - return NULL; + if (info == nullptr) { + return nullptr; } - if (ginfo != NULL) { + if (ginfo != nullptr) { return &ginfo->def_value; } return &info->def_value; @@ -876,12 +876,12 @@ AP_Param::find_object(const char *name) if (strcasecmp(name, _var_info[i].name) == 0) { ptrdiff_t base; if (!get_base(_var_info[i], base)) { - return NULL; + return nullptr; } return (AP_Param *)base; } } - return NULL; + return nullptr; } // notify GCS of current value of parameter @@ -892,7 +892,7 @@ void AP_Param::notify() const { uint8_t idx; const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx); - if (info == NULL) { + if (info == nullptr) { // this is probably very bad return; } @@ -901,7 +901,7 @@ void AP_Param::notify() const { copy_name_info(info, ginfo, group_nesting, idx, name, sizeof(name), true); uint32_t param_header_type; - if (ginfo != NULL) { + if (ginfo != nullptr) { param_header_type = ginfo->type; } else { param_header_type = info->type; @@ -922,7 +922,7 @@ bool AP_Param::save(bool force_save) const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx); const AP_Param *ap; - if (info == NULL) { + if (info == nullptr) { // we don't have any info on how to store it return false; } @@ -930,7 +930,7 @@ bool AP_Param::save(bool force_save) struct Param_header phdr; // create the header we will use to store the variable - if (ginfo != NULL) { + if (ginfo != nullptr) { phdr.type = ginfo->type; } else { phdr.type = info->type; @@ -971,7 +971,7 @@ bool AP_Param::save(bool force_save) if (phdr.type <= AP_PARAM_FLOAT) { float v1 = cast_to_float((enum ap_var_type)phdr.type); float v2; - if (ginfo != NULL) { + if (ginfo != nullptr) { v2 = get_default_value(&ginfo->def_value); } else { v2 = get_default_value(&info->def_value); @@ -1014,7 +1014,7 @@ bool AP_Param::load(void) struct GroupNesting group_nesting {}; uint8_t idx; const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx); - if (info == NULL) { + if (info == nullptr) { // we don't have any info on how to load it return false; } @@ -1022,7 +1022,7 @@ bool AP_Param::load(void) struct Param_header phdr; // create the header we will use to match the variable - if (ginfo != NULL) { + if (ginfo != nullptr) { phdr.type = ginfo->type; } else { phdr.type = info->type; @@ -1039,7 +1039,7 @@ bool AP_Param::load(void) return false; } - if (ginfo != NULL) { + if (ginfo != nullptr) { // add in nested group offset ptrdiff_t group_offset = 0; for (uint8_t i=0; itype; } else { phdr.type = info->type; @@ -1107,14 +1107,14 @@ bool AP_Param::configured_in_defaults_file(void) struct GroupNesting group_nesting {}; uint8_t idx; const struct AP_Param::Info *info = find_var_info(&group_element, ginfo, group_nesting, &idx); - if (info == NULL) { + if (info == nullptr) { // we don't have any info on how to load it return false; } const float* def_value_ptr; - if (ginfo != NULL) { + if (ginfo != nullptr) { def_value_ptr = &ginfo->def_value; } else { def_value_ptr = &info->def_value; @@ -1242,7 +1242,7 @@ bool AP_Param::load_all(void) void *ptr; info = find_by_header(phdr, &ptr); - if (info != NULL) { + if (info != nullptr) { _storage.read_block(ptr, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type)); } @@ -1293,7 +1293,7 @@ void AP_Param::load_object_from_eeprom(const void *object_pointer, const struct void *ptr; info = find_by_header(phdr, &ptr); - if (info != NULL) { + if (info != nullptr) { if ((ptrdiff_t)ptr == ((ptrdiff_t)object_pointer)+group_info[i].offset) { _storage.read_block(ptr, ofs+sizeof(phdr), type_size((enum ap_var_type)phdr.type)); break; @@ -1313,15 +1313,15 @@ AP_Param *AP_Param::first(ParamToken *token, enum ap_var_type *ptype) token->group_element = 0; token->idx = 0; if (_num_vars == 0) { - return NULL; + return nullptr; } - if (ptype != NULL) { + if (ptype != nullptr) { *ptype = (enum ap_var_type)_var_info[0].type; } ptrdiff_t base; if (!get_base(_var_info[0], base)) { // should be impossible, first var needs to be non-pointer - return NULL; + return nullptr; } return (AP_Param *)base; } @@ -1352,7 +1352,7 @@ AP_Param *AP_Param::next_group(uint16_t vindex, const struct GroupInfo *group_in ap = next_group(vindex, ginfo, found_current, group_id(group_info, group_base, i, group_shift), group_shift + _group_level_shift, new_offset, token, ptype); - if (ap != NULL) { + if (ap != nullptr) { return ap; } } else { @@ -1361,7 +1361,7 @@ AP_Param *AP_Param::next_group(uint16_t vindex, const struct GroupInfo *group_in token->key = vindex; token->group_element = group_id(group_info, group_base, i, group_shift); token->idx = 0; - if (ptype != NULL) { + if (ptype != nullptr) { *ptype = type; } ptrdiff_t base; @@ -1376,7 +1376,7 @@ AP_Param *AP_Param::next_group(uint16_t vindex, const struct GroupInfo *group_in // return the next element of the vector as a // float token->idx++; - if (ptype != NULL) { + if (ptype != nullptr) { *ptype = AP_PARAM_FLOAT; } ptrdiff_t base; @@ -1390,7 +1390,7 @@ AP_Param *AP_Param::next_group(uint16_t vindex, const struct GroupInfo *group_in } } } - return NULL; + return nullptr; } /// Returns the next variable in _var_info, recursing into groups @@ -1401,7 +1401,7 @@ AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype) bool found_current = false; if (i >= _num_vars) { // illegal token - return NULL; + return nullptr; } enum ap_var_type type = (enum ap_var_type)_var_info[i].type; @@ -1409,7 +1409,7 @@ AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype) // then as 3 separate floats if (type == AP_PARAM_VECTOR3F && token->idx < 3) { token->idx++; - if (ptype != NULL) { + if (ptype != nullptr) { *ptype = AP_PARAM_FLOAT; } return (AP_Param *)(((token->idx - 1u)*sizeof(float))+(ptrdiff_t)_var_info[i].ptr); @@ -1424,7 +1424,7 @@ AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype) if (type == AP_PARAM_GROUP) { const struct GroupInfo *group_info = _var_info[i].group_info; AP_Param *ap = next_group(i, group_info, &found_current, 0, 0, 0, token, ptype); - if (ap != NULL) { + if (ap != nullptr) { return ap; } } else { @@ -1432,13 +1432,13 @@ AP_Param *AP_Param::next(ParamToken *token, enum ap_var_type *ptype) token->key = i; token->group_element = 0; token->idx = 0; - if (ptype != NULL) { + if (ptype != nullptr) { *ptype = type; } return (AP_Param *)(_var_info[i].ptr); } } - return NULL; + return nullptr; } /// Returns the next scalar in _var_info, recursing into groups @@ -1447,9 +1447,9 @@ AP_Param *AP_Param::next_scalar(ParamToken *token, enum ap_var_type *ptype) { AP_Param *ap; enum ap_var_type type; - while ((ap = next(token, &type)) != NULL && type > AP_PARAM_FLOAT) ; + while ((ap = next(token, &type)) != nullptr && type > AP_PARAM_FLOAT) ; - if (ap != NULL && type == AP_PARAM_INT8) { + if (ap != nullptr && type == AP_PARAM_INT8) { /* check if this is an enable variable. To do that we need to find the info structures for the variable @@ -1472,7 +1472,7 @@ AP_Param *AP_Param::next_scalar(ParamToken *token, enum ap_var_type *ptype) ParamToken token2 = *token; enum ap_var_type type2; AP_Param *ap2; - while ((ap2 = next(&token2, &type2)) != NULL) { + while ((ap2 = next(&token2, &type2)) != nullptr) { if (token2.key != token->key) { break; } @@ -1486,7 +1486,7 @@ AP_Param *AP_Param::next_scalar(ParamToken *token, enum ap_var_type *ptype) } } - if (ap != NULL && ptype != NULL) { + if (ap != nullptr && ptype != nullptr) { *ptype = type; } return ap; @@ -1587,7 +1587,7 @@ void AP_Param::convert_old_parameter(const struct ConversionInfo *info, float sc enum ap_var_type ptype; AP_Param *ap2; ap2 = find(&info->new_name[0], &ptype); - if (ap2 == NULL) { + if (ap2 == nullptr) { hal.console->printf("Unknown conversion '%s'\n", info->new_name); return; } @@ -1679,16 +1679,16 @@ bool AP_Param::parse_param_line(char *line, char **vname, float &value) if (line[0] == '#') { return false; } - char *saveptr = NULL; + char *saveptr = nullptr; char *pname = strtok_r(line, ", =\t", &saveptr); - if (pname == NULL) { + if (pname == nullptr) { return false; } if (strlen(pname) > AP_MAX_NAME_SIZE) { return false; } - const char *value_s = strtok_r(NULL, ", =\t", &saveptr); - if (value_s == NULL) { + const char *value_s = strtok_r(nullptr, ", =\t", &saveptr); + if (value_s == nullptr) { return false; } value = atof(value_s); @@ -1705,7 +1705,7 @@ bool AP_Param::load_defaults_file(const char *filename) return false; } FILE *f = fopen(filename, "r"); - if (f == NULL) { + if (f == nullptr) { return false; } char line[100]; @@ -1730,13 +1730,13 @@ bool AP_Param::load_defaults_file(const char *filename) } fclose(f); - if (param_overrides != NULL) { + if (param_overrides != nullptr) { free(param_overrides); } num_param_overrides = 0; param_overrides = new param_override[num_defaults]; - if (param_overrides == NULL) { + if (param_overrides == nullptr) { AP_HAL::panic("AP_Param: Failed to allocate overrides"); return false; } @@ -1745,7 +1745,7 @@ bool AP_Param::load_defaults_file(const char *filename) re-open to avoid possible seek issues with NuttX */ f = fopen(filename, "r"); - if (f == NULL) { + if (f == nullptr) { AP_HAL::panic("AP_Param: Failed to re-open defaults file"); return false; } @@ -1841,10 +1841,10 @@ uint16_t AP_Param::count_parameters(void) AP_Param *vp; AP_Param::ParamToken token; - vp = AP_Param::first(&token, NULL); + vp = AP_Param::first(&token, nullptr); do { _parameter_count++; - } while (NULL != (vp = AP_Param::next_scalar(&token, NULL))); + } while (nullptr != (vp = AP_Param::next_scalar(&token, nullptr))); } return _parameter_count; } diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 1cf8fb0291..826a62c97e 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -73,8 +73,8 @@ // declare a pointer subgroup entry in a group var_info #define AP_SUBGROUPPTR(element, name, idx, thisclazz, elclazz) { AP_PARAM_GROUP, idx, name, AP_VAROFFSET(thisclazz, element), { group_info : elclazz::var_info }, AP_PARAM_FLAG_POINTER } -#define AP_GROUPEND { AP_PARAM_NONE, 0xFF, "", 0, { group_info : NULL } } -#define AP_VAREND { AP_PARAM_NONE, "", 0, NULL, { group_info : NULL } } +#define AP_GROUPEND { AP_PARAM_NONE, 0xFF, "", 0, { group_info : nullptr } } +#define AP_VAREND { AP_PARAM_NONE, "", 0, nullptr, { group_info : nullptr } } enum ap_var_type { AP_PARAM_NONE = 0, @@ -197,7 +197,7 @@ public: /// If the variable has no name, it cannot be found by this interface. /// /// @param name The full name of the variable to be found. - /// @return A pointer to the variable, or NULL if + /// @return A pointer to the variable, or nullptr if /// it does not exist. /// static AP_Param * find(const char *name, enum ap_var_type *ptype); @@ -213,7 +213,7 @@ public: /// /// /// @param idx The index of the variable - /// @return A pointer to the variable, or NULL if + /// @return A pointer to the variable, or nullptr if /// it does not exist. /// static AP_Param * find_by_index(uint16_t idx, enum ap_var_type *ptype, ParamToken *token); @@ -315,7 +315,7 @@ public: /// Returns the first variable /// - /// @return The first variable in _var_info, or NULL if + /// @return The first variable in _var_info, or nullptr if /// there are none. /// static AP_Param * first(ParamToken *token, enum ap_var_type *ptype); diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index c7effc4c0e..572bcec3b9 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/libraries/AP_Proximity/AP_Proximity.cpp @@ -87,7 +87,7 @@ void AP_Proximity::init(void) } for (uint8_t i=0; i=0; i--) { - if (drivers[i] != NULL && (state[i].status == Proximity_Good)) { + if (drivers[i] != nullptr && (state[i].status == Proximity_Good)) { primary_instance = i; } } @@ -173,7 +173,7 @@ void AP_Proximity::detect_instance(uint8_t instance) // returns true on successful read and places distance in distance bool AP_Proximity::get_horizontal_distance(uint8_t instance, float angle_deg, float &distance) const { - if ((drivers[instance] == NULL) || (_type[instance] == Proximity_Type_None)) { + if ((drivers[instance] == nullptr) || (_type[instance] == Proximity_Type_None)) { return false; } // get distance from backend diff --git a/libraries/AP_RPM/AP_RPM.cpp b/libraries/AP_RPM/AP_RPM.cpp index b4a59f6485..aca574a392 100644 --- a/libraries/AP_RPM/AP_RPM.cpp +++ b/libraries/AP_RPM/AP_RPM.cpp @@ -109,7 +109,7 @@ void AP_RPM::init(void) state[instance].instance = instance; drivers[instance] = new AP_RPM_SITL(*this, instance, state[instance]); #endif - if (drivers[i] != NULL) { + if (drivers[i] != nullptr) { // we loaded a driver for this instance, so it must be // present (although it may not be healthy) num_instances = i+1; @@ -123,7 +123,7 @@ void AP_RPM::init(void) void AP_RPM::update(void) { for (uint8_t i=0; iget_device("bebop")); _gpio = AP_HAL::get_HAL().gpio; - if (_gpio == NULL) { + if (_gpio == nullptr) { AP_HAL::panic("Could not find GPIO device for Bebop ultrasound"); } diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp index 795c352f0f..6fcb83d1dc 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp @@ -35,7 +35,7 @@ AP_RangeFinder_analog::AP_RangeFinder_analog(RangeFinder &_ranger, uint8_t insta AP_RangeFinder_Backend(_ranger, instance, _state) { source = hal.analogin->channel(ranger._pin[instance]); - if (source == NULL) { + if (source == nullptr) { // failed to allocate a ADC channel? This shouldn't happen set_status(RangeFinder::RangeFinder_NotConnected); return; @@ -64,7 +64,7 @@ bool AP_RangeFinder_analog::detect(RangeFinder &_ranger, uint8_t instance) */ void AP_RangeFinder_analog::update_voltage(void) { - if (source == NULL) { + if (source == nullptr) { state.voltage_mv = 0; return; } diff --git a/libraries/AP_RangeFinder/RangeFinder.cpp b/libraries/AP_RangeFinder/RangeFinder.cpp index 3fb524dc36..32881851c9 100644 --- a/libraries/AP_RangeFinder/RangeFinder.cpp +++ b/libraries/AP_RangeFinder/RangeFinder.cpp @@ -521,7 +521,7 @@ void RangeFinder::init(void) } for (uint8_t i=0; i=0; i--) { - if (drivers[i] != NULL && (state[i].status == RangeFinder_Good)) { + if (drivers[i] != nullptr && (state[i].status == RangeFinder_Good)) { primary_instance = i; } } @@ -680,7 +680,7 @@ RangeFinder::RangeFinder_Status RangeFinder::status(uint8_t instance) const return RangeFinder_NotConnected; } - if (drivers[instance] == NULL || _type[instance] == RangeFinder_TYPE_NONE) { + if (drivers[instance] == nullptr || _type[instance] == RangeFinder_TYPE_NONE) { return RangeFinder_NotConnected; } @@ -690,7 +690,7 @@ RangeFinder::RangeFinder_Status RangeFinder::status(uint8_t instance) const void RangeFinder::handle_msg(mavlink_message_t *msg) { uint8_t i; for (i=0; ihandle_msg(msg); } } @@ -715,7 +715,7 @@ bool RangeFinder::pre_arm_check() const { for (uint8_t i=0; iset_blocking_writes(blocking); } } diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index 39e42dff61..d01d34104d 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -95,7 +95,7 @@ public: // find_serial - searches available serial ports that allows the given protocol // instance should be zero if searching for the first instance, 1 for the second, etc - // returns uart on success, NULL if a serial port cannot be found + // returns uart on success, nullptr if a serial port cannot be found AP_HAL::UARTDriver *find_serial(enum SerialProtocol protocol, uint8_t instance) const; // find_baudrate - searches available serial ports for the first instance that allows the given protocol diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index 00e88d21db..e4c8d8b88c 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -412,7 +412,7 @@ private: // grid spacing during rally check uint16_t last_rally_spacing; - char *file_path = NULL; + char *file_path = nullptr; // status enum TerrainStatus system_status = TerrainStatusDisabled; diff --git a/libraries/AP_Terrain/TerrainIO.cpp b/libraries/AP_Terrain/TerrainIO.cpp index a6d6cbf080..e87077924c 100644 --- a/libraries/AP_Terrain/TerrainIO.cpp +++ b/libraries/AP_Terrain/TerrainIO.cpp @@ -149,18 +149,18 @@ void AP_Terrain::open_file(void) // already open on right file return; } - if (file_path == NULL) { + if (file_path == nullptr) { const char* terrain_dir = hal.util->get_custom_terrain_directory(); - if (terrain_dir == NULL) { + if (terrain_dir == nullptr) { terrain_dir = HAL_BOARD_TERRAIN_DIRECTORY; } if (asprintf(&file_path, "%s/NxxExxx.DAT", terrain_dir) <= 0) { io_failure = true; - file_path = NULL; + file_path = nullptr; return; } } - if (file_path == NULL) { + if (file_path == nullptr) { io_failure = true; return; } diff --git a/libraries/DataFlash/DFMessageWriter.cpp b/libraries/DataFlash/DFMessageWriter.cpp index b180c9c40d..9b5eed2e0e 100644 --- a/libraries/DataFlash/DFMessageWriter.cpp +++ b/libraries/DataFlash/DFMessageWriter.cpp @@ -143,7 +143,7 @@ void DFMessageWriter_WriteEntireMission::process() { switch(stage) { case em_blockwriter_stage_init: - if (_mission == NULL) { + if (_mission == nullptr) { stage = em_blockwriter_stage_done; break; } else { diff --git a/libraries/DataFlash/DataFlash_Backend.cpp b/libraries/DataFlash/DataFlash_Backend.cpp index b24bd887ca..f9a8a7e763 100644 --- a/libraries/DataFlash/DataFlash_Backend.cpp +++ b/libraries/DataFlash/DataFlash_Backend.cpp @@ -147,7 +147,7 @@ bool DataFlash_Backend::Log_Write(const uint8_t msg_type, va_list arg_list, bool // stack-allocate a buffer so we can WriteBlock(); this could be // 255 bytes! If we were willing to lose the WriteBlock // abstraction we could do WriteBytes() here instead? - const char *fmt = NULL; + const char *fmt = nullptr; uint8_t msg_len; DataFlash_Class::log_write_fmt *f; for (f = _front.log_write_fmts; f; f=f->next) { @@ -157,7 +157,7 @@ bool DataFlash_Backend::Log_Write(const uint8_t msg_type, va_list arg_list, bool break; } } - if (fmt == NULL) { + if (fmt == nullptr) { // this is a bug. internal_error(); return false; diff --git a/libraries/DataFlash/DataFlash_Block.cpp b/libraries/DataFlash/DataFlash_Block.cpp index 41397282c3..204b6f054d 100644 --- a/libraries/DataFlash/DataFlash_Block.cpp +++ b/libraries/DataFlash/DataFlash_Block.cpp @@ -72,7 +72,7 @@ bool DataFlash_Block::WritePrioritisedBlock(const void *pBuffer, uint16_t size, BlockWrite(df_BufferNum, df_BufferIdx, &ph, sizeof(ph), pBuffer, n); df_BufferIdx += n + sizeof(ph); } else { - BlockWrite(df_BufferNum, df_BufferIdx, NULL, 0, pBuffer, n); + BlockWrite(df_BufferNum, df_BufferIdx, nullptr, 0, pBuffer, n); df_BufferIdx += n; } diff --git a/libraries/DataFlash/DataFlash_File.cpp b/libraries/DataFlash/DataFlash_File.cpp index 0ba0a74670..69e54e36a4 100644 --- a/libraries/DataFlash/DataFlash_File.cpp +++ b/libraries/DataFlash/DataFlash_File.cpp @@ -100,7 +100,7 @@ void DataFlash_File::Init() // try to cope with an existing lowercase log directory // name. NuttX does not handle case insensitive VFAT well DIR *d = opendir("/fs/microsd/APM"); - if (d != NULL) { + if (d != nullptr) { for (struct dirent *de=readdir(d); de; de=readdir(d)) { if (strcmp(de->d_name, "logs") == 0) { rename("/fs/microsd/APM/logs", "/fs/microsd/APM/OLDLOGS"); @@ -112,7 +112,7 @@ void DataFlash_File::Init() #endif const char* custom_dir = hal.util->get_custom_log_directory(); - if (custom_dir != NULL){ + if (custom_dir != nullptr){ _log_directory = custom_dir; } @@ -173,7 +173,7 @@ bool DataFlash_File::file_exists(const char *filename) const bool DataFlash_File::log_exists(const uint16_t lognum) const { char *filename = _log_file_name(lognum); - if (filename == NULL) { + if (filename == nullptr) { // internal_error(); return false; // ?! } @@ -272,7 +272,7 @@ uint16_t DataFlash_File::find_oldest_log() // relying on the min_avail_space_percent feature we could end up // doing a *lot* of asprintf()s and stat()s DIR *d = opendir(_log_directory); - if (d == NULL) { + if (d == nullptr) { // internal_error(); return 0; } @@ -289,7 +289,7 @@ uint16_t DataFlash_File::find_oldest_log() continue; } - uint16_t thisnum = strtoul(de->d_name, NULL, 10); + uint16_t thisnum = strtoul(de->d_name, nullptr, 10); if (thisnum > MAX_LOG_FILES) { // ignore files above our official maximum... continue; @@ -348,7 +348,7 @@ void DataFlash_File::Prep_MinSpace() break; } char *filename_to_remove = _log_file_name(log_to_remove); - if (filename_to_remove == NULL) { + if (filename_to_remove == nullptr) { // internal_error(); break; } @@ -408,9 +408,9 @@ bool DataFlash_File::NeedPrep() */ char *DataFlash_File::_log_file_name(const uint16_t log_num) const { - char *buf = NULL; + char *buf = nullptr; if (asprintf(&buf, "%s/%u.BIN", _log_directory, (unsigned)log_num) == 0) { - return NULL; + return nullptr; } return buf; } @@ -421,9 +421,9 @@ char *DataFlash_File::_log_file_name(const uint16_t log_num) const */ char *DataFlash_File::_lastlog_file_name(void) const { - char *buf = NULL; + char *buf = nullptr; if (asprintf(&buf, "%s/LASTLOG.TXT", _log_directory) == 0) { - return NULL; + return nullptr; } return buf; } @@ -438,14 +438,14 @@ void DataFlash_File::EraseAll() #if !DATAFLASH_FILE_MINIMAL for (log_num=1; log_num<=MAX_LOG_FILES; log_num++) { char *fname = _log_file_name(log_num); - if (fname == NULL) { + if (fname == nullptr) { break; } unlink(fname); free(fname); } char *fname = _lastlog_file_name(); - if (fname != NULL) { + if (fname != nullptr) { unlink(fname); free(fname); } @@ -533,7 +533,7 @@ uint16_t DataFlash_File::find_last_log() { unsigned ret = 0; char *fname = _lastlog_file_name(); - if (fname == NULL) { + if (fname == nullptr) { return ret; } int fd = open(fname, O_RDONLY); @@ -555,7 +555,7 @@ uint32_t DataFlash_File::_get_log_size(const uint16_t log_num) const return 1; #else char *fname = _log_file_name(log_num); - if (fname == NULL) { + if (fname == nullptr) { return 0; } struct stat st; @@ -574,7 +574,7 @@ uint32_t DataFlash_File::_get_log_time(const uint16_t log_num) const return 0; #else char *fname = _log_file_name(log_num); - if (fname == NULL) { + if (fname == nullptr) { return 0; } struct stat st; @@ -647,7 +647,7 @@ int16_t DataFlash_File::get_log_data(const uint16_t list_entry, const uint16_t p } if (_read_fd == -1) { char *fname = _log_file_name(log_num); - if (fname == NULL) { + if (fname == nullptr) { return -1; } stop_logging(); @@ -801,7 +801,7 @@ uint16_t DataFlash_File::start_new_log(void) log_num = 1; } char *fname = _log_file_name(log_num); - if (fname == NULL) { + if (fname == nullptr) { return 0xFFFF; } _write_fd = ::open(fname, O_WRONLY|O_CREAT|O_TRUNC, 0666); @@ -870,7 +870,7 @@ void DataFlash_File::LogReadProcess(const uint16_t list_entry, _read_fd = -1; } char *fname = _log_file_name(log_num); - if (fname == NULL) { + if (fname == nullptr) { return; } _read_fd = ::open(fname, O_RDONLY); @@ -974,7 +974,7 @@ void DataFlash_File::ListAvailableLogs(AP_HAL::BetterStream *port) for (uint16_t i=1; i<=num_logs; i++) { uint16_t log_num = _log_num_from_list_entry(i); char *filename = _log_file_name(log_num); - if (filename != NULL) { + if (filename != nullptr) { struct stat st; if (stat(filename, &st) == 0) { struct tm *tm = gmtime(&st.st_mtime); diff --git a/libraries/DataFlash/DataFlash_MAVLink.cpp b/libraries/DataFlash/DataFlash_MAVLink.cpp index 8b258ee50c..908debec25 100644 --- a/libraries/DataFlash/DataFlash_MAVLink.cpp +++ b/libraries/DataFlash/DataFlash_MAVLink.cpp @@ -27,16 +27,16 @@ void DataFlash_MAVLink::Init() { DataFlash_Backend::Init(); - _blocks = NULL; + _blocks = nullptr; while (_blockcount >= 8) { // 8 is a *magic* number _blocks = (struct dm_block *) malloc(_blockcount * sizeof(_blocks[0])); - if (_blocks != NULL) { + if (_blocks != nullptr) { break; } _blockcount /= 2; } - if (_blocks == NULL) { + if (_blocks == nullptr) { return; } @@ -66,7 +66,7 @@ uint8_t DataFlash_MAVLink::remaining_space_in_current_block() { void DataFlash_MAVLink::enqueue_block(dm_block_queue_t &queue, struct dm_block *block) { - if (queue.youngest != NULL) { + if (queue.youngest != nullptr) { queue.youngest->next = block; } else { queue.oldest = block; @@ -76,13 +76,13 @@ void DataFlash_MAVLink::enqueue_block(dm_block_queue_t &queue, struct dm_block * struct DataFlash_MAVLink::dm_block *DataFlash_MAVLink::dequeue_seqno(DataFlash_MAVLink::dm_block_queue_t &queue, uint32_t seqno) { - struct dm_block *prev = NULL; - for (struct dm_block *block=queue.oldest; block != NULL; block=block->next) { + struct dm_block *prev = nullptr; + for (struct dm_block *block=queue.oldest; block != nullptr; block=block->next) { if (block->seqno == seqno) { - if (prev == NULL) { + if (prev == nullptr) { if (queue.youngest == queue.oldest) { - queue.oldest = NULL; - queue.youngest = NULL; + queue.oldest = nullptr; + queue.youngest = nullptr; } else { queue.oldest = block->next; } @@ -92,18 +92,18 @@ struct DataFlash_MAVLink::dm_block *DataFlash_MAVLink::dequeue_seqno(DataFlash_M } prev->next = block->next; } - block->next = NULL; + block->next = nullptr; return block; } prev = block; } - return NULL; + return nullptr; } bool DataFlash_MAVLink::free_seqno_from_queue(uint32_t seqno, dm_block_queue_t &queue) { struct dm_block *block = dequeue_seqno(queue, seqno); - if (block != NULL) { + if (block != nullptr) { block->next = _blocks_free; _blocks_free = block; _blockcount_free++; // comment me out to expose a bug! @@ -136,9 +136,9 @@ bool DataFlash_MAVLink::WritePrioritisedBlock(const void *pBuffer, uint16_t size uint16_t copied = 0; while (copied < size) { - if (_current_block == NULL) { + if (_current_block == nullptr) { _current_block = next_block(); - if (_current_block == NULL) { + if (_current_block == nullptr) { // should not happen - there's a sanity check above internal_error(); return false; @@ -168,12 +168,12 @@ bool DataFlash_MAVLink::WritePrioritisedBlock(const void *pBuffer, uint16_t size struct DataFlash_MAVLink::dm_block *DataFlash_MAVLink::next_block() { DataFlash_MAVLink::dm_block *ret = _blocks_free; - if (ret != NULL) { + if (ret != nullptr) { _blocks_free = ret->next; _blockcount_free--; ret->seqno = _next_seq_num++; ret->last_sent = 0; - ret->next = NULL; + ret->next = nullptr; _latest_block_len = 0; } return ret; @@ -181,15 +181,15 @@ struct DataFlash_MAVLink::dm_block *DataFlash_MAVLink::next_block() void DataFlash_MAVLink::free_all_blocks() { - _blocks_free = NULL; - _current_block = NULL; + _blocks_free = nullptr; + _current_block = nullptr; _blocks_pending.sent_count = 0; - _blocks_pending.oldest = _blocks_pending.youngest = NULL; + _blocks_pending.oldest = _blocks_pending.youngest = nullptr; _blocks_retry.sent_count = 0; - _blocks_retry.oldest = _blocks_retry.youngest = NULL; + _blocks_retry.oldest = _blocks_retry.youngest = nullptr; _blocks_sent.sent_count = 0; - _blocks_sent.oldest = _blocks_sent.youngest = NULL; + _blocks_sent.oldest = _blocks_sent.youngest = nullptr; // add blocks to the free stack: for(uint8_t i=0; i < _blockcount; i++) { @@ -231,7 +231,7 @@ void DataFlash_MAVLink::handle_ack(mavlink_channel_t chan, Debug("Starting New Log"); free_all_blocks(); // _current_block = next_block(); - // if (_current_block == NULL) { + // if (_current_block == nullptr) { // Debug("No free blocks?!!!\n"); // return; // } @@ -279,7 +279,7 @@ void DataFlash_MAVLink::handle_retry(uint32_t seqno) } struct dm_block *victim = dequeue_seqno(_blocks_sent, seqno); - if (victim != NULL) { + if (victim != nullptr) { _last_response_time = AP_HAL::millis(); enqueue_block(_blocks_retry, victim); } @@ -380,7 +380,7 @@ void DataFlash_MAVLink::stats_log() uint8_t DataFlash_MAVLink::stack_size(struct dm_block *stack) { uint8_t ret = 0; - for (struct dm_block *block=stack; block != NULL; block=block->next) { + for (struct dm_block *block=stack; block != nullptr; block=block->next) { ret++; } return ret; @@ -442,7 +442,7 @@ void DataFlash_MAVLink::stats_collect() bool DataFlash_MAVLink::send_log_blocks_from_queue(dm_block_queue_t &queue) { uint8_t sent_count = 0; - while (queue.oldest != NULL) { + while (queue.oldest != nullptr) { if (sent_count++ > _max_blocks_per_send_blocks) { return false; } @@ -451,7 +451,7 @@ bool DataFlash_MAVLink::send_log_blocks_from_queue(dm_block_queue_t &queue) } queue.sent_count++; struct DataFlash_MAVLink::dm_block *tmp = dequeue_seqno(queue,queue.oldest->seqno); - if (tmp != NULL) { // should never be NULL + if (tmp != nullptr) { // should never be nullptr enqueue_block(_blocks_sent, tmp); } else { internal_error(); @@ -489,7 +489,7 @@ void DataFlash_MAVLink::do_resends(uint32_t now) } uint32_t oldest = now - 100; // 100 milliseconds before resend. Hmm. while (count_to_send-- > 0) { - for (struct dm_block *block=_blocks_sent.oldest; block != NULL; block=block->next) { + for (struct dm_block *block=_blocks_sent.oldest; block != nullptr; block=block->next) { // only want to send blocks every now-and-then: if (block->last_sent < oldest) { if (! send_log_block(*block)) { diff --git a/libraries/DataFlash/DataFlash_SITL.h b/libraries/DataFlash/DataFlash_SITL.h index 866331dc88..09c2142661 100644 --- a/libraries/DataFlash/DataFlash_SITL.h +++ b/libraries/DataFlash/DataFlash_SITL.h @@ -27,7 +27,7 @@ private: // write size bytes of data to a page. The caller must ensure that // the data fits within the page, otherwise it will wrap to the // start of the page - // If pHeader is not NULL then write the header bytes before the data + // If pHeader is not nullptr then write the header bytes before the data void BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr, const void *pHeader, uint8_t hdr_size, const void *pBuffer, uint16_t size); diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index 332628041c..f44b64a2b5 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -35,14 +35,14 @@ void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_ty _params.backend_types == DATAFLASH_BACKEND_BOTH) { DFMessageWriter_DFLogStart *message_writer = new DFMessageWriter_DFLogStart(_firmware_string); - if (message_writer != NULL) { + if (message_writer != nullptr) { #if HAL_OS_POSIX_IO backends[_next_backend] = new DataFlash_File(*this, message_writer, HAL_BOARD_LOG_DIRECTORY); #endif } - if (backends[_next_backend] == NULL) { + if (backends[_next_backend] == nullptr) { hal.console->printf("Unable to open DataFlash_File"); } else { _next_backend++; @@ -59,11 +59,11 @@ void DataFlash_Class::Init(const struct LogStructure *structures, uint8_t num_ty } DFMessageWriter_DFLogStart *message_writer = new DFMessageWriter_DFLogStart(_firmware_string); - if (message_writer != NULL) { + if (message_writer != nullptr) { backends[_next_backend] = new DataFlash_MAVLink(*this, message_writer); } - if (backends[_next_backend] == NULL) { + if (backends[_next_backend] == nullptr) { hal.console->printf("Unable to open DataFlash_MAVLink"); } else { _next_backend++; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index a9ca33874f..003cfefe2e 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -54,7 +54,7 @@ GCS_MAVLINK::init(AP_HAL::UARTDriver *port, mavlink_channel_t mav_chan) mavlink_comm_port[chan] = _port; initialised = true; - _queued_parameter = NULL; + _queued_parameter = nullptr; reset_cli_timeout(); } @@ -71,7 +71,7 @@ GCS_MAVLINK::setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager AP_HAL::UARTDriver *uart; uart = serial_manager.find_serial(protocol, instance); - if (uart == NULL) { + if (uart == nullptr) { // return immediately if not found return; } @@ -120,7 +120,7 @@ GCS_MAVLINK::setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager // load signing key load_signing_key(); - if (status->signing == NULL) { + if (status->signing == nullptr) { // if signing is off start by sending MAVLink1. status->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1; } @@ -145,7 +145,7 @@ GCS_MAVLINK::setup_uart(const AP_SerialManager& serial_manager, AP_SerialManager void GCS_MAVLINK::queued_param_send() { - if (!initialised || _queued_parameter == NULL) { + if (!initialised || _queued_parameter == nullptr) { return; } @@ -167,7 +167,7 @@ GCS_MAVLINK::queued_param_send() count = 5; } - while (_queued_parameter != NULL && count--) { + while (_queued_parameter != nullptr && count--) { AP_Param *vp; float value; @@ -486,7 +486,7 @@ bool GCS_MAVLINK::have_flow_control(void) return false; } - if (mavlink_comm_port[chan] == NULL) { + if (mavlink_comm_port[chan] == nullptr) { return false; } @@ -519,7 +519,7 @@ void GCS_MAVLINK::handle_request_data_stream(mavlink_message_t *msg, bool save) else return; - AP_Int16 *rate = NULL; + AP_Int16 *rate = nullptr; switch (packet.req_stream_id) { case MAV_DATA_STREAM_ALL: // note that we don't set STREAM_PARAMS - that is internal only @@ -557,7 +557,7 @@ void GCS_MAVLINK::handle_request_data_stream(mavlink_message_t *msg, bool save) break; } - if (rate != NULL) { + if (rate != nullptr) { if (save) { rate->set_and_save_ifchanged(freq); } else { @@ -606,7 +606,7 @@ void GCS_MAVLINK::handle_param_request_read(mavlink_message_t *msg) if (packet.param_index != -1) { AP_Param::ParamToken token; vp = AP_Param::find_by_index(packet.param_index, &p_type, &token); - if (vp == NULL) { + if (vp == nullptr) { return; } vp->copy_name_token(token, param_name, AP_MAX_NAME_SIZE, true); @@ -615,7 +615,7 @@ void GCS_MAVLINK::handle_param_request_read(mavlink_message_t *msg) strncpy(param_name, packet.param_id, AP_MAX_NAME_SIZE); param_name[AP_MAX_NAME_SIZE] = 0; vp = AP_Param::find(param_name, &p_type); - if (vp == NULL) { + if (vp == nullptr) { return; } } @@ -645,7 +645,7 @@ void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg, DataFlash_Class *Data // find existing param so we can get the old value vp = AP_Param::find(key, &var_type); - if (vp == NULL) { + if (vp == nullptr) { return; } float old_value = vp->cast_to_float(var_type); @@ -665,7 +665,7 @@ void GCS_MAVLINK::handle_param_set(mavlink_message_t *msg, DataFlash_Class *Data // save the change vp->save(force_save); - if (DataFlash != NULL) { + if (DataFlash != nullptr) { DataFlash->Log_Write_Parameter(key, vp->cast_to_float(var_type)); } } @@ -975,12 +975,12 @@ void GCS_MAVLINK::packetReceived(const mavlink_status_t &status, // currently sending MAVLink1 then switch to sending // MAVLink2 mavlink_status_t *cstatus = mavlink_get_channel_status(chan); - if (cstatus != NULL) { + if (cstatus != nullptr) { cstatus->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1; } } // if a snoop handler has been setup then use it - if (msg_snoop != NULL) { + if (msg_snoop != nullptr) { msg_snoop(&msg); } if (routing.check_and_forward(chan, &msg) && @@ -1342,7 +1342,7 @@ void GCS_MAVLINK::send_statustext_chan(MAV_SEVERITY severity, uint8_t dest_chan, */ void GCS_MAVLINK::send_statustext(MAV_SEVERITY severity, uint8_t dest_bitmask, const char *text) { - if (dataflash_p != NULL) { + if (dataflash_p != nullptr) { dataflash_p->Log_Write_Message(text); } @@ -1670,7 +1670,7 @@ float GCS_MAVLINK::adjust_rate_for_stream_trigger(enum streams stream_num) // send at a much lower rate while handling waypoints and // parameter sends if ((stream_num != STREAM_PARAMS) && - (waypoint_receiving || _queued_parameter != NULL)) { + (waypoint_receiving || _queued_parameter != nullptr)) { return 0.25f; } diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.cpp b/libraries/GCS_MAVLink/GCS_MAVLink.cpp index b8fffbc6e4..19e0cbcf1a 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.cpp +++ b/libraries/GCS_MAVLink/GCS_MAVLink.cpp @@ -49,7 +49,7 @@ const AP_SerialManager *GCS_MAVLINK::serialmanager_p; // snoop function for vehicle types that want to see messages for // other targets -void (*GCS_MAVLINK::msg_snoop)(const mavlink_message_t* msg) = NULL; +void (*GCS_MAVLINK::msg_snoop)(const mavlink_message_t* msg) = nullptr; /* lock a channel, preventing use by MAVLink @@ -155,5 +155,5 @@ extern const AP_HAL::HAL& hal; bool comm_is_idle(mavlink_channel_t chan) { mavlink_status_t *status = mavlink_get_channel_status(chan); - return status == NULL || status->parse_state <= MAVLINK_PARSE_STATE_IDLE; + return status == nullptr || status->parse_state <= MAVLINK_PARSE_STATE_IDLE; } diff --git a/libraries/GCS_MAVLink/GCS_Signing.cpp b/libraries/GCS_MAVLink/GCS_Signing.cpp index 1c5edd99e7..c59877d0c9 100644 --- a/libraries/GCS_MAVLink/GCS_Signing.cpp +++ b/libraries/GCS_MAVLink/GCS_Signing.cpp @@ -120,7 +120,7 @@ void GCS_MAVLINK::load_signing_key(void) return; } mavlink_status_t *status = mavlink_get_channel_status(chan); - if (status == NULL) { + if (status == nullptr) { hal.console->printf("Failed to load signing key - no status"); return; } @@ -144,11 +144,11 @@ void GCS_MAVLINK::load_signing_key(void) // enable signing on all channels for (uint8_t i=0; isigning = NULL; - cstatus->signing_streams = NULL; + cstatus->signing = nullptr; + cstatus->signing_streams = nullptr; } else { cstatus->signing = &signing; cstatus->signing_streams = &signing_streams; diff --git a/libraries/GCS_MAVLink/GCS_serial_control.cpp b/libraries/GCS_MAVLink/GCS_serial_control.cpp index 4f9d16a24f..75fc2ca34a 100644 --- a/libraries/GCS_MAVLink/GCS_serial_control.cpp +++ b/libraries/GCS_MAVLink/GCS_serial_control.cpp @@ -32,8 +32,8 @@ void GCS_MAVLINK::handle_serial_control(mavlink_message_t *msg, AP_GPS &gps) mavlink_serial_control_t packet; mavlink_msg_serial_control_decode(msg, &packet); - AP_HAL::UARTDriver *port = NULL; - AP_HAL::Stream *stream = NULL; + AP_HAL::UARTDriver *port = nullptr; + AP_HAL::Stream *stream = nullptr; if (packet.flags & SERIAL_CONTROL_FLAG_REPLY) { // how did this packet get to us? @@ -67,7 +67,7 @@ void GCS_MAVLINK::handle_serial_control(mavlink_message_t *msg, AP_GPS &gps) return; } - if (exclusive && port != NULL) { + if (exclusive && port != nullptr) { // force flow control off for exclusive access. This protocol // is used to talk to bootloaders which may not have flow // control support @@ -75,7 +75,7 @@ void GCS_MAVLINK::handle_serial_control(mavlink_message_t *msg, AP_GPS &gps) } // optionally change the baudrate - if (packet.baudrate != 0 && port != NULL) { + if (packet.baudrate != 0 && port != nullptr) { port->begin(packet.baudrate); } diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 012196eccd..c5800cb1a3 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -198,7 +198,7 @@ void RC_Channel::set_pwm_all(void) { for (uint8_t i=0; iset_pwm(_rc_ch[i]->read()); } } @@ -490,7 +490,7 @@ void RC_Channel::output_trim() void RC_Channel::output_trim_all() { for (uint8_t i=0; ioutput_trim(); } } @@ -502,7 +502,7 @@ void RC_Channel::output_trim_all() void RC_Channel::setup_failsafe_trim_mask(uint16_t chmask) { for (uint8_t i=0; iset_failsafe_pwm(1U<_radio_trim); } } @@ -543,7 +543,7 @@ RC_Channel::disable_out() RC_Channel *RC_Channel::rc_channel(uint8_t i) { if (i >= RC_MAX_CHANNELS) { - return NULL; + return nullptr; } return _rc_ch[i]; } diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index 184a732ff8..b40b26d60f 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -88,7 +88,7 @@ void RC_Channel_aux::disable_aux_channel(uint8_t channel) { for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) { if (_aux_channels[i] && _aux_channels[i]->_ch_out == channel) { - _aux_channels[i] = NULL; + _aux_channels[i] = nullptr; } } } @@ -165,7 +165,7 @@ void RC_Channel_aux::update_aux_servo_function(void) // set auxiliary ranges for (uint8_t i = 0; i < RC_AUX_MAX_CHANNELS; i++) { - if (_aux_channels[i] == NULL) continue; + if (_aux_channels[i] == nullptr) continue; _aux_channels[i]->aux_servo_function_setup(); } _initialised = true; diff --git a/libraries/RC_Channel/RC_Channel_aux.h b/libraries/RC_Channel/RC_Channel_aux.h index d5020ddb3d..84bd1c1268 100644 --- a/libraries/RC_Channel/RC_Channel_aux.h +++ b/libraries/RC_Channel/RC_Channel_aux.h @@ -21,7 +21,7 @@ public: RC_Channel(ch_out) { for (uint8_t i=0; i\n" @@ -133,7 +133,7 @@ bool JSBSim::create_templates(void) char *jsbsim_reset; asprintf(&jsbsim_reset, "%s/aircraft/%s/reset.xml", autotest_dir, jsbsim_model); f = fopen(jsbsim_reset, "w"); - if (f == NULL) { + if (f == nullptr) { AP_HAL::panic("Unable to create jsbsim reset script %s", jsbsim_reset); } float r, p, y; @@ -206,7 +206,7 @@ bool JSBSim::start_JSBSim(void) "--simulation-rate=1000", logdirective, script, - NULL); + nullptr); if (ret != 0) { perror("JSBSim"); } @@ -321,7 +321,7 @@ bool JSBSim::open_fdm_socket(void) */ void JSBSim::send_servos(const struct sitl_input &input) { - char *buf = NULL; + char *buf = nullptr; float aileron = filtered_servo_angle(input, 0); float elevator = filtered_servo_angle(input, 1); float throttle = filtered_servo_range(input, 2); diff --git a/libraries/SITL/SIM_Multicopter.cpp b/libraries/SITL/SIM_Multicopter.cpp index e6ee3e744b..1f4e980fdf 100644 --- a/libraries/SITL/SIM_Multicopter.cpp +++ b/libraries/SITL/SIM_Multicopter.cpp @@ -25,12 +25,12 @@ using namespace SITL; MultiCopter::MultiCopter(const char *home_str, const char *frame_str) : Aircraft(home_str, frame_str), - frame(NULL) + frame(nullptr) { mass = 1.5f; frame = Frame::find_frame(frame_str); - if (frame == NULL) { + if (frame == nullptr) { printf("Frame '%s' not found", frame_str); exit(1); } diff --git a/libraries/SITL/SIM_Rover.cpp b/libraries/SITL/SIM_Rover.cpp index d956dc6a5e..c4ad53671b 100644 --- a/libraries/SITL/SIM_Rover.cpp +++ b/libraries/SITL/SIM_Rover.cpp @@ -32,7 +32,7 @@ SimRover::SimRover(const char *home_str, const char *frame_str) : skid_turn_rate(140), // degrees/sec skid_steering(false) { - skid_steering = strstr(frame_str, "skid") != NULL; + skid_steering = strstr(frame_str, "skid") != nullptr; if (skid_steering) { printf("SKID Steering Rover Simulation Started\n"); diff --git a/libraries/SITL/SIM_last_letter.cpp b/libraries/SITL/SIM_last_letter.cpp index acf0b3699d..3de4ca09f6 100644 --- a/libraries/SITL/SIM_last_letter.cpp +++ b/libraries/SITL/SIM_last_letter.cpp @@ -64,7 +64,7 @@ void last_letter::start_last_letter(void) "last_letter", "gazebo.launch", "ArduPlane:=true", - NULL); + nullptr); if (ret != 0) { perror("roslaunch"); }