From dcd3f83539842d743f248c03c21f26419f4da554 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Patrick=20Jos=C3=A9=20Pereira?= Date: Thu, 28 Jun 2018 08:09:40 -0300 Subject: [PATCH] Sub: Remove void as parameter MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Patrick José Pereira --- ArduSub/ArduSub.cpp | 6 +++--- ArduSub/GCS_Mavlink.cpp | 8 ++++---- ArduSub/Log.cpp | 4 ++-- ArduSub/Parameters.cpp | 6 +++--- ArduSub/Sub.cpp | 2 +- ArduSub/capabilities.cpp | 2 +- ArduSub/control_auto.cpp | 2 +- ArduSub/failsafe.cpp | 4 ++-- ArduSub/sensors.cpp | 8 ++++---- 9 files changed, 21 insertions(+), 21 deletions(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 0dedf063e3..6befe3c98c 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -164,7 +164,7 @@ void Sub::fifty_hz_loop() // update_batt_compass - read battery and compass // should be called at 10hz -void Sub::update_batt_compass(void) +void Sub::update_batt_compass() { // read battery before compass because it may be used for motor interference compensation battery.read(); @@ -292,7 +292,7 @@ void Sub::one_hz_loop() } // called at 50hz -void Sub::update_GPS(void) +void Sub::update_GPS() { static uint32_t last_gps_reading[GPS_MAX_INSTANCES]; // time of last gps message bool gps_updated = false; @@ -315,7 +315,7 @@ void Sub::update_GPS(void) } } -void Sub::read_AHRS(void) +void Sub::read_AHRS() { // Perform IMU calculations and get attitude info //----------------------------------------------- diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 39f98120dc..2d97f440ec 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -5,12 +5,12 @@ // default sensors are present and healthy: gyro, accelerometer, rate_control, attitude_stabilization, yaw_position, altitude control, x/y position control, motor_control #define MAVLINK_SENSOR_PRESENT_DEFAULT (MAV_SYS_STATUS_SENSOR_3D_GYRO | MAV_SYS_STATUS_SENSOR_3D_ACCEL | MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL | MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION | MAV_SYS_STATUS_SENSOR_YAW_POSITION | MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL | MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL | MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS | MAV_SYS_STATUS_AHRS | MAV_SYS_STATUS_SENSOR_BATTERY) -void Sub::gcs_send_heartbeat(void) +void Sub::gcs_send_heartbeat() { gcs().send_message(MSG_HEARTBEAT); } -void Sub::gcs_send_deferred(void) +void Sub::gcs_send_deferred() { gcs().retry_deferred(); } @@ -1316,7 +1316,7 @@ void Sub::mavlink_delay_cb() /* * send data streams in the given rate range on both links */ -void Sub::gcs_data_stream_send(void) +void Sub::gcs_data_stream_send() { gcs().data_stream_send(); } @@ -1324,7 +1324,7 @@ void Sub::gcs_data_stream_send(void) /* * look for incoming commands on the GCS links */ -void Sub::gcs_check_input(void) +void Sub::gcs_check_input() { gcs().update(); } diff --git a/ArduSub/Log.cpp b/ArduSub/Log.cpp index 28a420e060..3bd9e044e9 100644 --- a/ArduSub/Log.cpp +++ b/ArduSub/Log.cpp @@ -5,7 +5,7 @@ // Code to Write and Read packets from DataFlash log memory // Code to interact with the user to dump or erase logs -void Sub::do_erase_logs(void) +void Sub::do_erase_logs() { gcs().send_text(MAV_SEVERITY_INFO, "Erasing logs"); DataFlash.EraseAll(); @@ -357,7 +357,7 @@ void Sub::Log_Write_Vehicle_Startup_Messages() } -void Sub::log_init(void) +void Sub::log_init() { DataFlash.Init(log_structure, ARRAY_SIZE(log_structure)); } diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index f0d2e76d5b..e975c9c98f 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -640,7 +640,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { /* constructor for g2 object */ -ParametersG2::ParametersG2(void) +ParametersG2::ParametersG2() #if PROXIMITY_ENABLED == ENABLED : proximity(sub.serial_manager) #endif @@ -654,7 +654,7 @@ const AP_Param::ConversionInfo conversion_table[] = { { Parameters::k_param_failsafe_battery_enabled, 0, AP_PARAM_INT8, "BATT_FS_LOW_ACT" }, }; -void Sub::load_parameters(void) +void Sub::load_parameters() { if (!AP_Param::check_var_info()) { hal.console->printf("Bad var table\n"); @@ -701,7 +701,7 @@ void Sub::load_parameters(void) AP_Param::set_default_by_name("MNT_JSTICK_SPD", 100); } -void Sub::convert_old_parameters(void) +void Sub::convert_old_parameters() { const uint8_t old_rc_keys[14] = { Parameters::k_param_rc_1_old, Parameters::k_param_rc_2_old, Parameters::k_param_rc_3_old, Parameters::k_param_rc_4_old, diff --git a/ArduSub/Sub.cpp b/ArduSub/Sub.cpp index 833d31fb91..0603e25a69 100644 --- a/ArduSub/Sub.cpp +++ b/ArduSub/Sub.cpp @@ -23,7 +23,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); /* constructor for main Sub class */ -Sub::Sub(void) +Sub::Sub() : DataFlash(g.log_bitmask), control_mode(MANUAL), motors(MAIN_LOOP_RATE), diff --git a/ArduSub/capabilities.cpp b/ArduSub/capabilities.cpp index 76fd7b127c..c7f07cf516 100644 --- a/ArduSub/capabilities.cpp +++ b/ArduSub/capabilities.cpp @@ -1,6 +1,6 @@ #include "Sub.h" -void Sub::init_capabilities(void) +void Sub::init_capabilities() { hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT); hal.util->set_capabilities(MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT); diff --git a/ArduSub/control_auto.cpp b/ArduSub/control_auto.cpp index 44e0b59145..7a257afb88 100644 --- a/ArduSub/control_auto.cpp +++ b/ArduSub/control_auto.cpp @@ -572,7 +572,7 @@ void Sub::set_auto_yaw_roi(const Location &roi_location) // get_auto_heading - returns target heading depending upon auto_yaw_mode // 100hz update rate -float Sub::get_auto_heading(void) +float Sub::get_auto_heading() { switch (auto_yaw_mode) { diff --git a/ArduSub/failsafe.cpp b/ArduSub/failsafe.cpp index 36e60a2641..1d36d53585 100644 --- a/ArduSub/failsafe.cpp +++ b/ArduSub/failsafe.cpp @@ -65,7 +65,7 @@ void Sub::mainloop_failsafe_check() } } -void Sub::failsafe_sensors_check(void) +void Sub::failsafe_sensors_check() { if (!ap.depth_sensor_present) { return; @@ -95,7 +95,7 @@ void Sub::failsafe_sensors_check(void) } } -void Sub::failsafe_ekf_check(void) +void Sub::failsafe_ekf_check() { static uint32_t last_ekf_good_ms = 0; diff --git a/ArduSub/sensors.cpp b/ArduSub/sensors.cpp index 6ff14af479..b627ee751d 100644 --- a/ArduSub/sensors.cpp +++ b/ArduSub/sensors.cpp @@ -1,7 +1,7 @@ #include "Sub.h" // return barometric altitude in centimeters -void Sub::read_barometer(void) +void Sub::read_barometer() { barometer.update(); @@ -10,7 +10,7 @@ void Sub::read_barometer(void) } } -void Sub::init_rangefinder(void) +void Sub::init_rangefinder() { #if RANGEFINDER_ENABLED == ENABLED rangefinder.init(); @@ -20,7 +20,7 @@ void Sub::init_rangefinder(void) } // return rangefinder altitude in centimeters -void Sub::read_rangefinder(void) +void Sub::read_rangefinder() { #if RANGEFINDER_ENABLED == ENABLED rangefinder.update(); @@ -96,7 +96,7 @@ void Sub::init_compass() if the compass is enabled then try to accumulate a reading also update initial location used for declination */ -void Sub::compass_accumulate(void) +void Sub::compass_accumulate() { if (!g.compass_enabled) { return;