From 152edf71891146abc588b86e5f4149405b794da1 Mon Sep 17 00:00:00 2001 From: Mathieu OTHACEHE Date: Sat, 22 Oct 2016 17:28:57 +0200 Subject: [PATCH] Global: remove mode line from headers Using a global .dir-locals.el file is a better alternative than reincluding the same emacs header in every file of the project. --- APMrover2/APM_Config.h | 2 -- APMrover2/APMrover2.cpp | 2 -- APMrover2/GCS_Mavlink.cpp | 2 -- APMrover2/Log.cpp | 2 -- APMrover2/Parameters.cpp | 2 -- APMrover2/Parameters.h | 1 - APMrover2/Rover.cpp | 1 - APMrover2/Rover.h | 1 - APMrover2/Steering.cpp | 2 -- APMrover2/capabilities.cpp | 2 -- APMrover2/commands.cpp | 2 -- APMrover2/commands_logic.cpp | 2 -- APMrover2/commands_process.cpp | 2 -- APMrover2/config.h | 1 - APMrover2/control_modes.cpp | 2 -- APMrover2/defines.h | 1 - APMrover2/events.cpp | 2 -- APMrover2/failsafe.cpp | 1 - APMrover2/navigation.cpp | 2 -- APMrover2/radio.cpp | 2 -- APMrover2/sensors.cpp | 2 -- APMrover2/setup.cpp | 2 -- APMrover2/system.cpp | 1 - APMrover2/test.cpp | 2 -- AntennaTracker/APM_Config.h | 2 -- AntennaTracker/AntennaTracker.cpp | 2 -- AntennaTracker/GCS_Mavlink.cpp | 2 -- AntennaTracker/Log.cpp | 2 -- AntennaTracker/Parameters.cpp | 2 -- AntennaTracker/Parameters.h | 1 - AntennaTracker/Tracker.h | 2 -- AntennaTracker/capabilities.cpp | 2 -- AntennaTracker/config.h | 1 - AntennaTracker/control_auto.cpp | 2 -- AntennaTracker/control_manual.cpp | 2 -- AntennaTracker/control_scan.cpp | 2 -- AntennaTracker/control_servo_test.cpp | 2 -- AntennaTracker/defines.h | 1 - AntennaTracker/radio.cpp | 2 -- AntennaTracker/sensors.cpp | 2 -- AntennaTracker/servos.cpp | 2 -- AntennaTracker/system.cpp | 2 -- AntennaTracker/tracking.cpp | 2 -- ArduCopter/APM_Config.h | 2 -- ArduCopter/APM_Config_mavlink_hil.h | 2 -- ArduCopter/AP_Rally.cpp | 1 - ArduCopter/AP_Rally.h | 1 - ArduCopter/AP_State.cpp | 2 -- ArduCopter/ArduCopter.cpp | 2 -- ArduCopter/Attitude.cpp | 2 -- ArduCopter/Copter.cpp | 2 -- ArduCopter/Copter.h | 1 - ArduCopter/GCS_Mavlink.cpp | 2 -- ArduCopter/Log.cpp | 2 -- ArduCopter/Parameters.cpp | 2 -- ArduCopter/Parameters.h | 1 - ArduCopter/UserCode.cpp | 2 -- ArduCopter/UserVariables.h | 2 -- ArduCopter/afs_copter.cpp | 2 -- ArduCopter/afs_copter.h | 1 - ArduCopter/arming_checks.cpp | 2 -- ArduCopter/baro_ground_effect.cpp | 2 -- ArduCopter/capabilities.cpp | 2 -- ArduCopter/commands.cpp | 2 -- ArduCopter/commands_logic.cpp | 2 -- ArduCopter/compassmot.cpp | 2 -- ArduCopter/config.h | 1 - ArduCopter/control_acro.cpp | 1 - ArduCopter/control_althold.cpp | 1 - ArduCopter/control_auto.cpp | 2 -- ArduCopter/control_autotune.cpp | 2 -- ArduCopter/control_avoid_adsb.cpp | 2 -- ArduCopter/control_brake.cpp | 2 -- ArduCopter/control_circle.cpp | 2 -- ArduCopter/control_drift.cpp | 2 -- ArduCopter/control_flip.cpp | 2 -- ArduCopter/control_guided.cpp | 2 -- ArduCopter/control_guided_nogps.cpp | 2 -- ArduCopter/control_land.cpp | 2 -- ArduCopter/control_loiter.cpp | 2 -- ArduCopter/control_poshold.cpp | 2 -- ArduCopter/control_rtl.cpp | 2 -- ArduCopter/control_sport.cpp | 2 -- ArduCopter/control_stabilize.cpp | 2 -- ArduCopter/control_throw.cpp | 2 -- ArduCopter/crash_check.cpp | 2 -- ArduCopter/defines.h | 1 - ArduCopter/ekf_check.cpp | 2 -- ArduCopter/esc_calibration.cpp | 2 -- ArduCopter/events.cpp | 2 -- ArduCopter/failsafe.cpp | 2 -- ArduCopter/fence.cpp | 2 -- ArduCopter/flight_mode.cpp | 2 -- ArduCopter/heli.cpp | 2 -- ArduCopter/heli_control_acro.cpp | 2 -- ArduCopter/heli_control_stabilize.cpp | 2 -- ArduCopter/inertia.cpp | 2 -- ArduCopter/land_detector.cpp | 2 -- ArduCopter/landing_gear.cpp | 2 -- ArduCopter/leds.cpp | 2 -- ArduCopter/motor_test.cpp | 2 -- ArduCopter/motors.cpp | 2 -- ArduCopter/navigation.cpp | 2 -- ArduCopter/perf_info.cpp | 2 -- ArduCopter/position_vector.cpp | 2 -- ArduCopter/precision_landing.cpp | 2 -- ArduCopter/radio.cpp | 2 -- ArduCopter/sensors.cpp | 2 -- ArduCopter/setup.cpp | 2 -- ArduCopter/switches.cpp | 2 -- ArduCopter/system.cpp | 2 -- ArduCopter/takeoff.cpp | 2 -- ArduCopter/terrain.cpp | 2 -- ArduCopter/test.cpp | 2 -- ArduCopter/tuning.cpp | 2 -- ArduPlane/APM_Config.h | 2 -- ArduPlane/ArduPlane.cpp | 2 -- ArduPlane/Attitude.cpp | 2 -- ArduPlane/GCS_Mavlink.cpp | 2 -- ArduPlane/Log.cpp | 2 -- ArduPlane/Parameters.cpp | 2 -- ArduPlane/Parameters.h | 1 - ArduPlane/Plane.cpp | 1 - ArduPlane/Plane.h | 1 - ArduPlane/afs_plane.cpp | 2 -- ArduPlane/altitude.cpp | 1 - ArduPlane/arming_checks.cpp | 1 - ArduPlane/capabilities.cpp | 2 -- ArduPlane/commands.cpp | 1 - ArduPlane/commands_logic.cpp | 2 -- ArduPlane/config.h | 1 - ArduPlane/control_modes.cpp | 2 -- ArduPlane/defines.h | 1 - ArduPlane/events.cpp | 2 -- ArduPlane/failsafe.cpp | 2 -- ArduPlane/geofence.cpp | 1 - ArduPlane/is_flying.cpp | 2 -- ArduPlane/landing.cpp | 2 -- ArduPlane/motor_test.cpp | 2 -- ArduPlane/navigation.cpp | 2 -- ArduPlane/parachute.cpp | 2 -- ArduPlane/px4_mixer.cpp | 2 -- ArduPlane/quadplane.cpp | 2 -- ArduPlane/quadplane.h | 2 -- ArduPlane/radio.cpp | 2 -- ArduPlane/sensors.cpp | 2 -- ArduPlane/servos.cpp | 1 - ArduPlane/setup.cpp | 2 -- ArduPlane/system.cpp | 2 -- ArduPlane/takeoff.cpp | 2 -- ArduPlane/test.cpp | 2 -- ArduPlane/tiltrotor.cpp | 2 -- ArduPlane/tuning.cpp | 2 -- ArduPlane/tuning.h | 2 -- Tools/CPUInfo/CPUInfo.cpp | 2 -- Tools/Hello/Hello.cpp | 2 -- Tools/Replay/Parameters.h | 1 - Tools/Replay/Replay.cpp | 1 - Tools/Replay/Replay.h | 1 - libraries/AC_AttitudeControl/AC_AttitudeControl.cpp | 2 -- libraries/AC_AttitudeControl/AC_AttitudeControl.h | 1 - libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp | 2 -- libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h | 1 - libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp | 2 -- libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h | 1 - libraries/AC_AttitudeControl/AC_PosControl.cpp | 1 - libraries/AC_AttitudeControl/AC_PosControl.h | 1 - libraries/AC_AttitudeControl/ControlMonitor.cpp | 2 -- libraries/AC_Fence/AC_Fence.cpp | 1 - libraries/AC_Fence/AC_Fence.h | 1 - libraries/AC_InputManager/AC_InputManager.cpp | 2 -- libraries/AC_InputManager/AC_InputManager.h | 1 - libraries/AC_InputManager/AC_InputManager_Heli.cpp | 2 -- libraries/AC_InputManager/AC_InputManager_Heli.h | 1 - libraries/AC_PID/AC_HELI_PID.cpp | 2 -- libraries/AC_PID/AC_HELI_PID.h | 1 - libraries/AC_PID/AC_P.cpp | 2 -- libraries/AC_PID/AC_P.h | 1 - libraries/AC_PID/AC_PID.cpp | 2 -- libraries/AC_PID/AC_PID.h | 1 - libraries/AC_PID/AC_PI_2D.cpp | 2 -- libraries/AC_PID/AC_PI_2D.h | 1 - libraries/AC_PrecLand/AC_PrecLand.cpp | 1 - libraries/AC_PrecLand/AC_PrecLand.h | 1 - libraries/AC_PrecLand/AC_PrecLand_Backend.h | 1 - libraries/AC_PrecLand/AC_PrecLand_Companion.cpp | 1 - libraries/AC_PrecLand/AC_PrecLand_Companion.h | 1 - libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp | 1 - libraries/AC_PrecLand/AC_PrecLand_IRLock.h | 1 - libraries/AC_PrecLand/PosVelEKF.h | 1 - libraries/AC_Sprayer/AC_Sprayer.cpp | 2 -- libraries/AC_Sprayer/AC_Sprayer.h | 2 -- libraries/AC_WPNav/AC_Circle.cpp | 1 - libraries/AC_WPNav/AC_Circle.h | 1 - libraries/AC_WPNav/AC_WPNav.cpp | 1 - libraries/AC_WPNav/AC_WPNav.h | 1 - libraries/APM_Control/AP_AutoTune.cpp | 2 -- libraries/APM_Control/AP_AutoTune.h | 1 - libraries/APM_Control/AP_PitchController.cpp | 1 - libraries/APM_Control/AP_PitchController.h | 1 - libraries/APM_Control/AP_RollController.cpp | 1 - libraries/APM_Control/AP_RollController.h | 1 - libraries/APM_Control/AP_SteerController.cpp | 1 - libraries/APM_Control/AP_SteerController.h | 1 - libraries/APM_Control/AP_YawController.cpp | 1 - libraries/APM_Control/AP_YawController.h | 1 - libraries/AP_ADC/AP_ADC_ADS1115.h | 1 - libraries/AP_ADSB/AP_ADSB.cpp | 1 - libraries/AP_ADSB/AP_ADSB.h | 1 - libraries/AP_AHRS/AP_AHRS.cpp | 1 - libraries/AP_AHRS/AP_AHRS.h | 1 - libraries/AP_AHRS/AP_AHRS_DCM.cpp | 1 - libraries/AP_AHRS/AP_AHRS_DCM.h | 1 - libraries/AP_AHRS/AP_AHRS_NavEKF.cpp | 1 - libraries/AP_AHRS/AP_AHRS_NavEKF.h | 1 - libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp | 2 -- libraries/AP_AccelCal/AP_AccelCal.cpp | 1 - libraries/AP_AccelCal/AccelCalibrator.cpp | 1 - libraries/AP_AccelCal/AccelCalibrator.h | 1 - libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp | 1 - libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h | 1 - libraries/AP_Airspeed/AP_Airspeed.cpp | 1 - libraries/AP_Airspeed/AP_Airspeed.h | 1 - libraries/AP_Airspeed/AP_Airspeed_Backend.h | 2 -- libraries/AP_Airspeed/AP_Airspeed_I2C.cpp | 2 -- libraries/AP_Airspeed/AP_Airspeed_I2C.h | 2 -- libraries/AP_Airspeed/AP_Airspeed_PX4.cpp | 1 - libraries/AP_Airspeed/AP_Airspeed_PX4.h | 2 -- libraries/AP_Airspeed/AP_Airspeed_analog.cpp | 1 - libraries/AP_Airspeed/AP_Airspeed_analog.h | 1 - libraries/AP_Airspeed/Airspeed_Calibration.cpp | 1 - libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp | 1 - libraries/AP_Arming/AP_Arming.cpp | 1 - libraries/AP_Arming/AP_Arming.h | 1 - libraries/AP_Avoidance/AP_Avoidance.h | 2 -- libraries/AP_Baro/AP_Baro.cpp | 1 - libraries/AP_Baro/AP_Baro.h | 1 - libraries/AP_Baro/AP_Baro_BMP085.cpp | 1 - libraries/AP_Baro/AP_Baro_BMP085.h | 1 - libraries/AP_Baro/AP_Baro_Backend.cpp | 1 - libraries/AP_Baro/AP_Baro_Backend.h | 1 - libraries/AP_Baro/AP_Baro_HIL.cpp | 1 - libraries/AP_Baro/AP_Baro_HIL.h | 1 - libraries/AP_Baro/AP_Baro_MS5611.cpp | 1 - libraries/AP_Baro/AP_Baro_MS5611.h | 1 - libraries/AP_Baro/AP_Baro_PX4.cpp | 1 - libraries/AP_Baro/AP_Baro_PX4.h | 1 - libraries/AP_Baro/AP_Baro_QURT.cpp | 1 - libraries/AP_Baro/AP_Baro_QURT.h | 1 - libraries/AP_Baro/AP_Baro_qflight.cpp | 1 - libraries/AP_Baro/AP_Baro_qflight.h | 1 - libraries/AP_BattMonitor/AP_BattMonitor.cpp | 1 - libraries/AP_BattMonitor/AP_BattMonitor.h | 1 - libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp | 1 - libraries/AP_BattMonitor/AP_BattMonitor_Analog.h | 1 - libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp | 1 - libraries/AP_BattMonitor/AP_BattMonitor_Backend.h | 1 - libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp | 1 - libraries/AP_BattMonitor/AP_BattMonitor_Bebop.h | 1 - libraries/AP_BattMonitor/AP_BattMonitor_SMBus.h | 1 - libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.cpp | 1 - libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.h | 1 - libraries/AP_BoardConfig/AP_BoardConfig.cpp | 1 - libraries/AP_BoardConfig/AP_BoardConfig.h | 1 - libraries/AP_BoardConfig/px4_drivers.cpp | 1 - libraries/AP_Buffer/AP_Buffer.h | 2 -- libraries/AP_Button/AP_Button.cpp | 1 - libraries/AP_Button/AP_Button.h | 1 - libraries/AP_Camera/AP_Camera.cpp | 2 -- libraries/AP_Camera/AP_Camera.h | 2 -- libraries/AP_Common/AP_Common.cpp | 1 - libraries/AP_Common/AP_Common.h | 1 - libraries/AP_Common/AP_Test.h | 1 - libraries/AP_Common/c++.cpp | 2 -- libraries/AP_Common/examples/AP_Common/AP_Common.cpp | 1 - libraries/AP_Compass/AP_Compass.cpp | 1 - libraries/AP_Compass/AP_Compass.h | 1 - libraries/AP_Compass/AP_Compass_AK8963.cpp | 1 - libraries/AP_Compass/AP_Compass_AK8963.h | 1 - libraries/AP_Compass/AP_Compass_BMM150.cpp | 1 - libraries/AP_Compass/AP_Compass_BMM150.h | 1 - libraries/AP_Compass/AP_Compass_Backend.cpp | 2 -- libraries/AP_Compass/AP_Compass_Backend.h | 1 - libraries/AP_Compass/AP_Compass_Calibration.cpp | 1 - libraries/AP_Compass/AP_Compass_HIL.cpp | 1 - libraries/AP_Compass/AP_Compass_HIL.h | 1 - libraries/AP_Compass/AP_Compass_HMC5843.cpp | 1 - libraries/AP_Compass/AP_Compass_HMC5843.h | 1 - libraries/AP_Compass/AP_Compass_LSM303D.cpp | 1 - libraries/AP_Compass/AP_Compass_LSM303D.h | 1 - libraries/AP_Compass/AP_Compass_PX4.cpp | 1 - libraries/AP_Compass/AP_Compass_PX4.h | 1 - libraries/AP_Compass/AP_Compass_QURT.cpp | 1 - libraries/AP_Compass/AP_Compass_QURT.h | 2 -- libraries/AP_Compass/AP_Compass_qflight.cpp | 1 - libraries/AP_Compass/AP_Compass_qflight.h | 2 -- libraries/AP_Compass/CompassCalibrator.cpp | 1 - libraries/AP_Compass/Compass_learn.cpp | 1 - libraries/AP_Declination/AP_Declination.cpp | 1 - libraries/AP_Declination/AP_Declination.h | 1 - .../examples/AP_Declination_test/AP_Declination_test.cpp | 2 -- libraries/AP_EPM/AP_EPM.cpp | 2 -- libraries/AP_EPM/AP_EPM.h | 2 -- libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp | 1 - libraries/AP_Frsky_Telem/AP_Frsky_Telem.h | 1 - libraries/AP_GPS/AP_GPS.cpp | 1 - libraries/AP_GPS/AP_GPS.h | 1 - libraries/AP_GPS/AP_GPS_ERB.cpp | 1 - libraries/AP_GPS/AP_GPS_ERB.h | 1 - libraries/AP_GPS/AP_GPS_GSOF.cpp | 1 - libraries/AP_GPS/AP_GPS_GSOF.h | 1 - libraries/AP_GPS/AP_GPS_MAV.cpp | 1 - libraries/AP_GPS/AP_GPS_MAV.h | 1 - libraries/AP_GPS/AP_GPS_MTK.cpp | 1 - libraries/AP_GPS/AP_GPS_MTK.h | 1 - libraries/AP_GPS/AP_GPS_MTK19.cpp | 1 - libraries/AP_GPS/AP_GPS_MTK19.h | 1 - libraries/AP_GPS/AP_GPS_MTK_Common.h | 1 - libraries/AP_GPS/AP_GPS_NMEA.cpp | 1 - libraries/AP_GPS/AP_GPS_NMEA.h | 1 - libraries/AP_GPS/AP_GPS_NOVA.cpp | 1 - libraries/AP_GPS/AP_GPS_NOVA.h | 1 - libraries/AP_GPS/AP_GPS_PX4.cpp | 1 - libraries/AP_GPS/AP_GPS_PX4.h | 1 - libraries/AP_GPS/AP_GPS_QURT.cpp | 1 - libraries/AP_GPS/AP_GPS_QURT.h | 1 - libraries/AP_GPS/AP_GPS_SBF.cpp | 1 - libraries/AP_GPS/AP_GPS_SBF.h | 1 - libraries/AP_GPS/AP_GPS_SBP.cpp | 1 - libraries/AP_GPS/AP_GPS_SBP.h | 1 - libraries/AP_GPS/AP_GPS_SIRF.cpp | 1 - libraries/AP_GPS/AP_GPS_SIRF.h | 1 - libraries/AP_GPS/AP_GPS_UBLOX.cpp | 1 - libraries/AP_GPS/AP_GPS_UBLOX.h | 1 - libraries/AP_GPS/GPS_Backend.cpp | 1 - libraries/AP_GPS/GPS_Backend.h | 1 - libraries/AP_GPS/GPS_detect_state.h | 1 - libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp | 1 - .../examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp | 1 - libraries/AP_GPS/tests/test_gps.cpp | 1 - libraries/AP_HAL/AP_HAL_Main.h | 1 - libraries/AP_HAL/Device.h | 1 - libraries/AP_HAL/I2CDevice.h | 1 - libraries/AP_HAL/SPIDevice.h | 1 - libraries/AP_HAL/UARTDriver.cpp | 1 - libraries/AP_HAL/utility/OwnPtr.h | 1 - libraries/AP_HAL/utility/dsm.cpp | 1 - libraries/AP_HAL/utility/functor.h | 1 - libraries/AP_HAL/utility/print_vprintf.cpp | 1 - libraries/AP_HAL/utility/srxl.cpp | 1 - libraries/AP_HAL/utility/srxl.h | 1 - libraries/AP_HAL/utility/st24.cpp | 1 - libraries/AP_HAL/utility/st24.h | 1 - libraries/AP_HAL/utility/sumd.cpp | 1 - libraries/AP_HAL/utility/sumd.h | 1 - libraries/AP_HAL/utility/tests/test_own_ptr.cpp | 1 - libraries/AP_HAL_Empty/I2CDevice.h | 1 - libraries/AP_HAL_Empty/SPIDevice.h | 1 - libraries/AP_HAL_Linux/AnalogIn_IIO.cpp | 1 - libraries/AP_HAL_Linux/AnalogIn_IIO.h | 1 - libraries/AP_HAL_Linux/Heat.h | 1 - libraries/AP_HAL_Linux/Heat_Pwm.cpp | 1 - libraries/AP_HAL_Linux/Heat_Pwm.h | 1 - libraries/AP_HAL_Linux/I2CDevice.cpp | 1 - libraries/AP_HAL_Linux/I2CDevice.h | 1 - libraries/AP_HAL_Linux/PWM_Sysfs.cpp | 1 - libraries/AP_HAL_Linux/Perf.cpp | 1 - libraries/AP_HAL_Linux/Perf.h | 1 - libraries/AP_HAL_Linux/Poller.cpp | 1 - libraries/AP_HAL_Linux/Poller.h | 1 - libraries/AP_HAL_Linux/PollerThread.cpp | 1 - libraries/AP_HAL_Linux/PollerThread.h | 1 - libraries/AP_HAL_Linux/RCInput_115200.cpp | 1 - libraries/AP_HAL_Linux/RCInput_DSM.cpp | 1 - libraries/AP_HAL_Linux/RCInput_Multi.cpp | 1 - libraries/AP_HAL_Linux/RCInput_SBUS.cpp | 1 - libraries/AP_HAL_Linux/RCOutput_AeroIO.cpp | 1 - libraries/AP_HAL_Linux/RCOutput_AeroIO.h | 1 - libraries/AP_HAL_Linux/RCOutput_Disco.cpp | 1 - libraries/AP_HAL_Linux/RCOutput_Sysfs.cpp | 1 - libraries/AP_HAL_Linux/RCOutput_qflight.cpp | 1 - libraries/AP_HAL_Linux/SPIDevice.cpp | 1 - libraries/AP_HAL_Linux/SPIDevice.h | 1 - libraries/AP_HAL_Linux/Thread.cpp | 1 - libraries/AP_HAL_Linux/Thread.h | 1 - libraries/AP_HAL_Linux/UARTDriver.cpp | 1 - libraries/AP_HAL_Linux/UARTQFlight.cpp | 1 - libraries/AP_HAL_Linux/qflight/dsp_functions.cpp | 1 - libraries/AP_HAL_Linux/sbus.cpp | 1 - libraries/AP_HAL_PX4/AnalogIn.cpp | 2 -- libraries/AP_HAL_PX4/AnalogIn.h | 1 - libraries/AP_HAL_PX4/GPIO.cpp | 2 -- libraries/AP_HAL_PX4/GPIO.h | 1 - libraries/AP_HAL_PX4/HAL_PX4_Class.cpp | 2 -- libraries/AP_HAL_PX4/I2CDevice.cpp | 1 - libraries/AP_HAL_PX4/I2CDevice.h | 1 - libraries/AP_HAL_PX4/NSHShellStream.cpp | 1 - libraries/AP_HAL_PX4/RCOutput.cpp | 2 -- libraries/AP_HAL_PX4/Scheduler.cpp | 2 -- libraries/AP_HAL_PX4/UARTDriver.cpp | 2 -- libraries/AP_HAL_PX4/examples/simple/simple.cpp | 2 -- libraries/AP_HAL_PX4/px4_param.cpp | 1 - libraries/AP_HAL_QURT/RCOutput.cpp | 1 - libraries/AP_HAL_QURT/Scheduler.cpp | 2 -- libraries/AP_HAL_SITL/AnalogIn.cpp | 2 -- libraries/AP_HAL_SITL/HAL_SITL_Class.cpp | 2 -- libraries/AP_HAL_SITL/SITL_State.cpp | 2 -- libraries/AP_HAL_SITL/SITL_cmdline.cpp | 2 -- libraries/AP_HAL_SITL/Scheduler.cpp | 2 -- libraries/AP_HAL_SITL/UARTDriver.cpp | 1 - libraries/AP_HAL_SITL/UARTDriver.h | 1 - libraries/AP_HAL_SITL/sitl_gps.cpp | 1 - libraries/AP_HAL_VRBRAIN/AnalogIn.cpp | 2 -- libraries/AP_HAL_VRBRAIN/AnalogIn.h | 1 - libraries/AP_HAL_VRBRAIN/GPIO.cpp | 2 -- libraries/AP_HAL_VRBRAIN/GPIO.h | 1 - libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp | 2 -- libraries/AP_HAL_VRBRAIN/I2CDevice.cpp | 1 - libraries/AP_HAL_VRBRAIN/I2CDevice.h | 1 - libraries/AP_HAL_VRBRAIN/NSHShellStream.cpp | 1 - libraries/AP_HAL_VRBRAIN/RCOutput.cpp | 2 -- libraries/AP_HAL_VRBRAIN/Scheduler.cpp | 2 -- libraries/AP_HAL_VRBRAIN/UARTDriver.cpp | 2 -- libraries/AP_HAL_VRBRAIN/vrbrain_param.cpp | 1 - libraries/AP_ICEngine/AP_ICEngine.cpp | 1 - libraries/AP_ICEngine/AP_ICEngine.h | 1 - libraries/AP_InertialNav/AP_InertialNav.h | 1 - libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp | 2 -- libraries/AP_InertialNav/AP_InertialNav_NavEKF.h | 2 -- libraries/AP_InertialSensor/AP_InertialSensor.cpp | 2 -- libraries/AP_InertialSensor/AP_InertialSensor.h | 1 - libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp | 2 -- libraries/AP_InertialSensor/AP_InertialSensor_Backend.h | 1 - libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp | 2 -- libraries/AP_InertialSensor/AP_InertialSensor_HIL.h | 1 - libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp | 1 - libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h | 1 - libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp | 2 -- libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h | 1 - libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp | 1 - libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.h | 1 - libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp | 2 -- libraries/AP_InertialSensor/AP_InertialSensor_PX4.h | 1 - libraries/AP_InertialSensor/AP_InertialSensor_QURT.cpp | 2 -- libraries/AP_InertialSensor/AP_InertialSensor_QURT.h | 1 - libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp | 2 -- libraries/AP_InertialSensor/AP_InertialSensor_SITL.h | 1 - .../AP_InertialSensor_UserInteract_MAVLink.cpp | 2 -- libraries/AP_InertialSensor/AP_InertialSensor_qflight.cpp | 2 -- libraries/AP_InertialSensor/AP_InertialSensor_qflight.h | 1 - libraries/AP_InertialSensor/AuxiliaryBus.h | 1 - .../AP_InertialSensor/examples/INS_generic/INS_generic.cpp | 2 -- libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp | 2 -- libraries/AP_L1_Control/AP_L1_Control.cpp | 2 -- libraries/AP_L1_Control/AP_L1_Control.h | 1 - libraries/AP_LandingGear/AP_LandingGear.cpp | 2 -- libraries/AP_LandingGear/AP_LandingGear.h | 2 -- libraries/AP_Math/edc.h | 1 - libraries/AP_Math/examples/eulers/eulers.cpp | 1 - libraries/AP_Math/examples/location/location.cpp | 1 - libraries/AP_Math/examples/matrix_alg/matrix_alg.cpp | 1 - libraries/AP_Math/examples/polygon/polygon.cpp | 1 - libraries/AP_Math/examples/rotations/rotations.cpp | 1 - libraries/AP_Math/location.cpp | 1 - libraries/AP_Math/matrix3.cpp | 1 - libraries/AP_Math/matrix3.h | 1 - libraries/AP_Math/matrix_alg.cpp | 1 - libraries/AP_Math/polygon.cpp | 1 - libraries/AP_Math/polygon.h | 1 - libraries/AP_Math/quaternion.cpp | 1 - libraries/AP_Math/quaternion.h | 1 - libraries/AP_Math/rotations.h | 1 - libraries/AP_Math/vector2.cpp | 1 - libraries/AP_Math/vector2.h | 1 - libraries/AP_Math/vector3.cpp | 1 - libraries/AP_Math/vector3.h | 1 - libraries/AP_Math/vectorN.h | 1 - libraries/AP_Menu/AP_Menu.cpp | 2 -- libraries/AP_Menu/AP_Menu.h | 2 -- libraries/AP_Mission/AP_Mission.cpp | 2 -- libraries/AP_Mission/AP_Mission.h | 2 -- libraries/AP_Module/AP_Module.cpp | 1 - libraries/AP_Module/AP_Module.h | 1 - libraries/AP_Module/AP_Module_Structures.h | 1 - libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp | 2 -- libraries/AP_Motors/AP_Motors.h | 1 - libraries/AP_Motors/AP_MotorsCoax.cpp | 1 - libraries/AP_Motors/AP_MotorsCoax.h | 2 -- libraries/AP_Motors/AP_MotorsHeli.cpp | 1 - libraries/AP_Motors/AP_MotorsHeli.h | 2 -- libraries/AP_Motors/AP_MotorsHeli_RSC.cpp | 1 - libraries/AP_Motors/AP_MotorsHeli_RSC.h | 1 - libraries/AP_Motors/AP_MotorsHeli_Single.cpp | 1 - libraries/AP_Motors/AP_MotorsHeli_Single.h | 2 -- libraries/AP_Motors/AP_MotorsHexa.cpp | 1 - libraries/AP_Motors/AP_MotorsHexa.h | 2 -- libraries/AP_Motors/AP_MotorsMatrix.cpp | 1 - libraries/AP_Motors/AP_MotorsMatrix.h | 2 -- libraries/AP_Motors/AP_MotorsMulticopter.cpp | 1 - libraries/AP_Motors/AP_MotorsMulticopter.h | 2 -- libraries/AP_Motors/AP_MotorsOcta.cpp | 1 - libraries/AP_Motors/AP_MotorsOcta.h | 2 -- libraries/AP_Motors/AP_MotorsOctaQuad.cpp | 1 - libraries/AP_Motors/AP_MotorsOctaQuad.h | 2 -- libraries/AP_Motors/AP_MotorsQuad.cpp | 1 - libraries/AP_Motors/AP_MotorsQuad.h | 2 -- libraries/AP_Motors/AP_MotorsSingle.cpp | 1 - libraries/AP_Motors/AP_MotorsSingle.h | 2 -- libraries/AP_Motors/AP_MotorsTri.cpp | 1 - libraries/AP_Motors/AP_MotorsTri.h | 2 -- libraries/AP_Motors/AP_MotorsY6.cpp | 1 - libraries/AP_Motors/AP_MotorsY6.h | 2 -- libraries/AP_Motors/AP_Motors_Class.cpp | 1 - libraries/AP_Motors/AP_Motors_Class.h | 1 - libraries/AP_Mount/AP_Mount.cpp | 2 -- libraries/AP_Mount/AP_Mount.h | 2 -- libraries/AP_Mount/AP_Mount_Alexmos.cpp | 1 - libraries/AP_Mount/AP_Mount_Alexmos.h | 2 -- libraries/AP_Mount/AP_Mount_Backend.cpp | 2 -- libraries/AP_Mount/AP_Mount_Backend.h | 1 - libraries/AP_Mount/AP_Mount_SToRM32.cpp | 2 -- libraries/AP_Mount/AP_Mount_SToRM32.h | 2 -- libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp | 2 -- libraries/AP_Mount/AP_Mount_SToRM32_serial.h | 2 -- libraries/AP_Mount/AP_Mount_Servo.cpp | 2 -- libraries/AP_Mount/AP_Mount_Servo.h | 2 -- libraries/AP_Mount/AP_Mount_SoloGimbal.cpp | 2 -- libraries/AP_Mount/AP_Mount_SoloGimbal.h | 2 -- libraries/AP_Mount/SoloGimbal.cpp | 2 -- libraries/AP_Mount/SoloGimbal.h | 2 -- libraries/AP_Mount/SoloGimbalEKF.cpp | 2 -- libraries/AP_Mount/SoloGimbalEKF.h | 1 - libraries/AP_NavEKF/AP_NavEKF.cpp | 2 -- libraries/AP_NavEKF/AP_NavEKF.h | 1 - libraries/AP_NavEKF/AP_NavEKF_core.cpp | 2 -- libraries/AP_NavEKF/AP_NavEKF_core.h | 1 - libraries/AP_NavEKF/AP_Nav_Common.h | 1 - libraries/AP_NavEKF2/AP_NavEKF2.cpp | 2 -- libraries/AP_NavEKF2/AP_NavEKF2.h | 1 - libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp | 2 -- libraries/AP_NavEKF2/AP_NavEKF2_Buffer.h | 2 -- libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp | 2 -- libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp | 2 -- libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp | 2 -- libraries/AP_NavEKF2/AP_NavEKF2_OptFlowFusion.cpp | 2 -- libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp | 2 -- libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp | 2 -- libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp | 2 -- libraries/AP_NavEKF2/AP_NavEKF2_core.cpp | 2 -- libraries/AP_NavEKF2/AP_NavEKF2_core.h | 1 - libraries/AP_NavEKF2/AP_NavEKF_GyroBias.cpp | 2 -- libraries/AP_Navigation/AP_Navigation.h | 2 -- libraries/AP_Notify/AP_BoardLED.cpp | 2 -- libraries/AP_Notify/AP_BoardLED.h | 2 -- libraries/AP_Notify/AP_Notify.cpp | 1 - libraries/AP_Notify/AP_Notify.h | 2 -- libraries/AP_Notify/Display.cpp | 2 -- libraries/AP_Notify/Display.h | 1 - libraries/AP_Notify/Display_SSD1306_I2C.cpp | 2 -- libraries/AP_Notify/Display_SSD1306_I2C.h | 1 - libraries/AP_Notify/ExternalLED.cpp | 2 -- libraries/AP_Notify/ExternalLED.h | 2 -- libraries/AP_Notify/RCOutputRGBLed.cpp | 1 - .../AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp | 2 -- libraries/AP_OpticalFlow/AP_OpticalFlow.h | 2 -- libraries/AP_OpticalFlow/AP_OpticalFlow_HIL.cpp | 1 - libraries/AP_OpticalFlow/AP_OpticalFlow_HIL.h | 1 - libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.cpp | 1 - libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.h | 2 -- libraries/AP_OpticalFlow/AP_OpticalFlow_PX4.cpp | 1 - libraries/AP_OpticalFlow/AP_OpticalFlow_PX4.h | 1 - libraries/AP_OpticalFlow/OpticalFlow.cpp | 2 -- libraries/AP_OpticalFlow/OpticalFlow_backend.cpp | 1 - libraries/AP_Parachute/AP_Parachute.cpp | 2 -- libraries/AP_Parachute/AP_Parachute.h | 2 -- libraries/AP_Param/AP_Param.cpp | 1 - libraries/AP_Param/AP_Param.h | 1 - libraries/AP_Proximity/AP_Proximity.cpp | 1 - libraries/AP_Proximity/AP_Proximity.h | 1 - libraries/AP_Proximity/AP_Proximity_Backend.cpp | 1 - libraries/AP_Proximity/AP_Proximity_Backend.h | 1 - libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp | 1 - libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h | 1 - libraries/AP_RCMapper/AP_RCMapper.cpp | 2 -- libraries/AP_RCMapper/AP_RCMapper.h | 1 - libraries/AP_RPM/AP_RPM.cpp | 1 - libraries/AP_RPM/AP_RPM.h | 1 - libraries/AP_RPM/RPM_Backend.cpp | 1 - libraries/AP_RPM/RPM_Backend.h | 1 - libraries/AP_RPM/RPM_PX4_PWM.cpp | 1 - libraries/AP_RPM/RPM_PX4_PWM.h | 1 - libraries/AP_RPM/RPM_SITL.cpp | 1 - libraries/AP_RPM/RPM_SITL.h | 1 - libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp | 1 - libraries/AP_RSSI/AP_RSSI.cpp | 1 - libraries/AP_RSSI/AP_RSSI.h | 1 - libraries/AP_Rally/AP_Rally.cpp | 2 -- libraries/AP_Rally/AP_Rally.h | 2 -- libraries/AP_RangeFinder/AP_RangeFinder.h | 2 -- libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp | 1 - libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h | 1 - libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp | 1 - libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h | 1 - libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp | 1 - libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h | 1 - libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp | 1 - libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h | 1 - libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp | 1 - libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h | 1 - libraries/AP_RangeFinder/AP_RangeFinder_PX4.cpp | 1 - libraries/AP_RangeFinder/AP_RangeFinder_PX4.h | 1 - libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.cpp | 1 - libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.h | 1 - libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp | 1 - libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h | 1 - libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp | 1 - libraries/AP_RangeFinder/AP_RangeFinder_analog.h | 1 - libraries/AP_RangeFinder/RangeFinder.cpp | 1 - libraries/AP_RangeFinder/RangeFinder.h | 1 - libraries/AP_RangeFinder/RangeFinder_Backend.cpp | 1 - libraries/AP_RangeFinder/RangeFinder_Backend.h | 1 - libraries/AP_Relay/AP_Relay.cpp | 2 -- libraries/AP_Relay/AP_Relay.h | 2 -- libraries/AP_Scheduler/AP_Scheduler.cpp | 1 - libraries/AP_Scheduler/AP_Scheduler.h | 1 - .../AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp | 2 -- libraries/AP_SerialManager/AP_SerialManager.cpp | 1 - libraries/AP_SerialManager/AP_SerialManager.h | 1 - libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp | 1 - libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.h | 2 -- libraries/AP_SpdHgtControl/AP_SpdHgtControl.h | 1 - libraries/AP_TECS/AP_TECS.cpp | 2 -- libraries/AP_TECS/AP_TECS.h | 2 -- libraries/AP_Terrain/AP_Terrain.cpp | 1 - libraries/AP_Terrain/AP_Terrain.h | 1 - libraries/AP_Terrain/TerrainGCS.cpp | 1 - libraries/AP_Terrain/TerrainIO.cpp | 1 - libraries/AP_Terrain/TerrainMission.cpp | 1 - libraries/AP_Terrain/TerrainUtil.cpp | 1 - libraries/AP_Tuning/AP_Tuning.cpp | 2 -- libraries/AP_Tuning/AP_Tuning.h | 2 -- libraries/DataFlash/DataFlash.h | 2 -- libraries/DataFlash/DataFlash_Block.cpp | 1 - libraries/DataFlash/DataFlash_Block.h | 2 -- libraries/DataFlash/DataFlash_File.cpp | 2 -- libraries/DataFlash/DataFlash_File.h | 2 -- libraries/DataFlash/DataFlash_MAVLink.cpp | 2 -- libraries/DataFlash/DataFlash_MAVLink.h | 2 -- libraries/DataFlash/DataFlash_SITL.cpp | 1 - libraries/DataFlash/LogFile.cpp | 2 -- .../examples/DataFlash_AllTypes/DataFlash_AllTypes.cpp | 1 - libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp | 1 - libraries/Filter/AverageFilter.h | 1 - libraries/Filter/DerivativeFilter.cpp | 1 - libraries/Filter/DerivativeFilter.h | 1 - libraries/Filter/FilterClass.h | 1 - libraries/Filter/FilterWithBuffer.h | 1 - libraries/Filter/LowPassFilter.h | 1 - libraries/Filter/LowPassFilter2p.h | 2 -- libraries/Filter/ModeFilter.h | 1 - libraries/GCS_Console/examples/Console/Console.cpp | 2 -- libraries/GCS_MAVLink/GCS.h | 2 -- libraries/GCS_MAVLink/GCS_Common.cpp | 2 -- libraries/GCS_MAVLink/GCS_Logs.cpp | 1 - libraries/GCS_MAVLink/GCS_MAVLink.cpp | 1 - libraries/GCS_MAVLink/GCS_MAVLink.h | 2 -- libraries/GCS_MAVLink/GCS_Signing.cpp | 2 -- libraries/GCS_MAVLink/GCS_serial_control.cpp | 1 - libraries/GCS_MAVLink/MAVLink_routing.cpp | 2 -- libraries/GCS_MAVLink/MAVLink_routing.h | 2 -- libraries/GCS_MAVLink/examples/routing/routing.cpp | 2 -- libraries/PID/PID.cpp | 2 -- libraries/PID/PID.h | 2 -- libraries/RC_Channel/RC_Channel.cpp | 1 - libraries/RC_Channel/RC_Channel.h | 2 -- libraries/RC_Channel/RC_Channel_aux.cpp | 2 -- libraries/RC_Channel/RC_Channel_aux.h | 2 -- libraries/RC_Channel/SRV_Channel.cpp | 1 - libraries/RC_Channel/SRV_Channel.h | 1 - libraries/SITL/SIM_ADSB.cpp | 1 - libraries/SITL/SIM_ADSB.h | 1 - libraries/SITL/SIM_Aircraft.cpp | 1 - libraries/SITL/SIM_Aircraft.h | 1 - libraries/SITL/SIM_Balloon.cpp | 1 - libraries/SITL/SIM_Balloon.h | 1 - libraries/SITL/SIM_CRRCSim.cpp | 1 - libraries/SITL/SIM_CRRCSim.h | 1 - libraries/SITL/SIM_FlightAxis.cpp | 1 - libraries/SITL/SIM_FlightAxis.h | 1 - libraries/SITL/SIM_Frame.cpp | 1 - libraries/SITL/SIM_Frame.h | 1 - libraries/SITL/SIM_Gazebo.cpp | 1 - libraries/SITL/SIM_Gazebo.h | 1 - libraries/SITL/SIM_Gimbal.cpp | 1 - libraries/SITL/SIM_Gimbal.h | 1 - libraries/SITL/SIM_Helicopter.cpp | 1 - libraries/SITL/SIM_Helicopter.h | 1 - libraries/SITL/SIM_ICEngine.cpp | 1 - libraries/SITL/SIM_ICEngine.h | 1 - libraries/SITL/SIM_JSBSim.cpp | 1 - libraries/SITL/SIM_JSBSim.h | 1 - libraries/SITL/SIM_Motor.cpp | 1 - libraries/SITL/SIM_Motor.h | 1 - libraries/SITL/SIM_Multicopter.cpp | 1 - libraries/SITL/SIM_Multicopter.h | 1 - libraries/SITL/SIM_Plane.cpp | 1 - libraries/SITL/SIM_Plane.h | 1 - libraries/SITL/SIM_QuadPlane.cpp | 1 - libraries/SITL/SIM_QuadPlane.h | 1 - libraries/SITL/SIM_Rover.cpp | 1 - libraries/SITL/SIM_Rover.h | 1 - libraries/SITL/SIM_SingleCopter.cpp | 1 - libraries/SITL/SIM_SingleCopter.h | 1 - libraries/SITL/SIM_Tracker.cpp | 1 - libraries/SITL/SIM_Tracker.h | 1 - libraries/SITL/SIM_XPlane.cpp | 1 - libraries/SITL/SIM_XPlane.h | 1 - libraries/SITL/SIM_last_letter.cpp | 1 - libraries/SITL/SIM_last_letter.h | 1 - libraries/SITL/SITL.cpp | 1 - libraries/SITL/SITL.h | 2 -- libraries/StorageManager/StorageManager.cpp | 1 - libraries/StorageManager/StorageManager.h | 1 - libraries/StorageManager/examples/StorageTest/StorageTest.cpp | 2 -- 724 files changed, 1010 deletions(-) diff --git a/APMrover2/APM_Config.h b/APMrover2/APM_Config.h index 8270b27cbf..98d4cd3b94 100644 --- a/APMrover2/APM_Config.h +++ b/APMrover2/APM_Config.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // This file is just a placeholder for your configuration file. If you wish to change any of the setup parameters from // their default values, place the appropriate #define statements here. diff --git a/APMrover2/APMrover2.cpp b/APMrover2/APMrover2.cpp index db5b43d192..86519adc56 100644 --- a/APMrover2/APMrover2.cpp +++ b/APMrover2/APMrover2.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index cb84df362a..d590c8626b 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" #include "version.h" diff --git a/APMrover2/Log.cpp b/APMrover2/Log.cpp index 715d5f0866..9379b8a64c 100644 --- a/APMrover2/Log.cpp +++ b/APMrover2/Log.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" #include "version.h" diff --git a/APMrover2/Parameters.cpp b/APMrover2/Parameters.cpp index bef06e9b04..06b5f9a452 100644 --- a/APMrover2/Parameters.cpp +++ b/APMrover2/Parameters.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" /* diff --git a/APMrover2/Parameters.h b/APMrover2/Parameters.h index 4c61d1080c..b62b434fbb 100644 --- a/APMrover2/Parameters.h +++ b/APMrover2/Parameters.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/APMrover2/Rover.cpp b/APMrover2/Rover.cpp index b10b25aeb8..56ce12d28e 100644 --- a/APMrover2/Rover.cpp +++ b/APMrover2/Rover.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/APMrover2/Rover.h b/APMrover2/Rover.h index 49cca6be0a..6689bc8a68 100644 --- a/APMrover2/Rover.h +++ b/APMrover2/Rover.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/APMrover2/Steering.cpp b/APMrover2/Steering.cpp index 51ba2cd2ac..e18460ea28 100644 --- a/APMrover2/Steering.cpp +++ b/APMrover2/Steering.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" /***************************************** diff --git a/APMrover2/capabilities.cpp b/APMrover2/capabilities.cpp index 9b4917a6f5..97b8636a34 100644 --- a/APMrover2/capabilities.cpp +++ b/APMrover2/capabilities.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" void Rover::init_capabilities(void) diff --git a/APMrover2/commands.cpp b/APMrover2/commands.cpp index 291f58e11a..4e7ab3fff6 100644 --- a/APMrover2/commands.cpp +++ b/APMrover2/commands.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" /* Functions in this file: diff --git a/APMrover2/commands_logic.cpp b/APMrover2/commands_logic.cpp index 0f58386f19..f6fdd0a79f 100644 --- a/APMrover2/commands_logic.cpp +++ b/APMrover2/commands_logic.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" /********************************************************************************/ diff --git a/APMrover2/commands_process.cpp b/APMrover2/commands_process.cpp index 1688d51320..19e5005ded 100644 --- a/APMrover2/commands_process.cpp +++ b/APMrover2/commands_process.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" // called by update navigation at 10Hz diff --git a/APMrover2/config.h b/APMrover2/config.h index 856071395a..21481830da 100644 --- a/APMrover2/config.h +++ b/APMrover2/config.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// diff --git a/APMrover2/control_modes.cpp b/APMrover2/control_modes.cpp index 46f84794dd..8f04d4ac71 100644 --- a/APMrover2/control_modes.cpp +++ b/APMrover2/control_modes.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" void Rover::read_control_switch() diff --git a/APMrover2/defines.h b/APMrover2/defines.h index 91c8df28c2..97b6cbdb57 100644 --- a/APMrover2/defines.h +++ b/APMrover2/defines.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once // Internal defines, don't edit and expect things to work diff --git a/APMrover2/events.cpp b/APMrover2/events.cpp index 736678d884..14252811cb 100644 --- a/APMrover2/events.cpp +++ b/APMrover2/events.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" void Rover::update_events(void) diff --git a/APMrover2/failsafe.cpp b/APMrover2/failsafe.cpp index eadf3ab150..9fdf4a9aa9 100644 --- a/APMrover2/failsafe.cpp +++ b/APMrover2/failsafe.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* failsafe support Andrew Tridgell, December 2011 diff --git a/APMrover2/navigation.cpp b/APMrover2/navigation.cpp index 10a19c458f..36ec0c282e 100644 --- a/APMrover2/navigation.cpp +++ b/APMrover2/navigation.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" //**************************************************************** diff --git a/APMrover2/radio.cpp b/APMrover2/radio.cpp index 5c5f36b3e1..13b9b772e9 100644 --- a/APMrover2/radio.cpp +++ b/APMrover2/radio.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" /* diff --git a/APMrover2/sensors.cpp b/APMrover2/sensors.cpp index 8110ab32b1..1457674319 100644 --- a/APMrover2/sensors.cpp +++ b/APMrover2/sensors.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" void Rover::init_barometer(bool full_calibration) diff --git a/APMrover2/setup.cpp b/APMrover2/setup.cpp index 3fcba92687..a8c70be3e2 100644 --- a/APMrover2/setup.cpp +++ b/APMrover2/setup.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" #if CLI_ENABLED == ENABLED diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 56b441ff5c..bbf93ceaa5 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /***************************************************************************** The init_ardupilot function processes everything we need for an in - air restart We will determine later if we are actually on the ground and process a diff --git a/APMrover2/test.cpp b/APMrover2/test.cpp index 21063fcd4c..b57f419c25 100644 --- a/APMrover2/test.cpp +++ b/APMrover2/test.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Rover.h" #if CLI_ENABLED == ENABLED diff --git a/AntennaTracker/APM_Config.h b/AntennaTracker/APM_Config.h index fe01a4d2b3..6a944de3bc 100644 --- a/AntennaTracker/APM_Config.h +++ b/AntennaTracker/APM_Config.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // This file is just a placeholder for your configuration file. If // you wish to change any of the setup parameters from their default // values, place the appropriate #define statements here. diff --git a/AntennaTracker/AntennaTracker.cpp b/AntennaTracker/AntennaTracker.cpp index 76c7469ad2..a236cbc64b 100644 --- a/AntennaTracker/AntennaTracker.cpp +++ b/AntennaTracker/AntennaTracker.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* Lead developers: Matthew Ridley and Andrew Tridgell diff --git a/AntennaTracker/GCS_Mavlink.cpp b/AntennaTracker/GCS_Mavlink.cpp index d487421f35..c4bf8ec54b 100644 --- a/AntennaTracker/GCS_Mavlink.cpp +++ b/AntennaTracker/GCS_Mavlink.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "GCS_Mavlink.h" #include "Tracker.h" diff --git a/AntennaTracker/Log.cpp b/AntennaTracker/Log.cpp index 0a52cb0550..bfc411b4e0 100644 --- a/AntennaTracker/Log.cpp +++ b/AntennaTracker/Log.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Tracker.h" #if LOGGING_ENABLED == ENABLED diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index ac2ed28935..90c2219ad2 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Tracker.h" /* diff --git a/AntennaTracker/Parameters.h b/AntennaTracker/Parameters.h index 47aba9084e..1ebae782ed 100644 --- a/AntennaTracker/Parameters.h +++ b/AntennaTracker/Parameters.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 291430f296..ad263fbe75 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* Lead developers: Matthew Ridley and Andrew Tridgell diff --git a/AntennaTracker/capabilities.cpp b/AntennaTracker/capabilities.cpp index 7af0df6307..9e237e95b1 100644 --- a/AntennaTracker/capabilities.cpp +++ b/AntennaTracker/capabilities.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Tracker.h" void Tracker::init_capabilities(void) diff --git a/AntennaTracker/config.h b/AntennaTracker/config.h index d1fadbe507..a788c9f85e 100644 --- a/AntennaTracker/config.h +++ b/AntennaTracker/config.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // #pragma once diff --git a/AntennaTracker/control_auto.cpp b/AntennaTracker/control_auto.cpp index 0a75691ebc..17616af75d 100644 --- a/AntennaTracker/control_auto.cpp +++ b/AntennaTracker/control_auto.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Tracker.h" /* diff --git a/AntennaTracker/control_manual.cpp b/AntennaTracker/control_manual.cpp index 76c5a79bc6..3322bdc15e 100644 --- a/AntennaTracker/control_manual.cpp +++ b/AntennaTracker/control_manual.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Tracker.h" /* diff --git a/AntennaTracker/control_scan.cpp b/AntennaTracker/control_scan.cpp index 121d810b3f..1932aacbd2 100644 --- a/AntennaTracker/control_scan.cpp +++ b/AntennaTracker/control_scan.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Tracker.h" /* diff --git a/AntennaTracker/control_servo_test.cpp b/AntennaTracker/control_servo_test.cpp index 42f63bb3bd..4aba496565 100644 --- a/AntennaTracker/control_servo_test.cpp +++ b/AntennaTracker/control_servo_test.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Tracker.h" /* diff --git a/AntennaTracker/defines.h b/AntennaTracker/defines.h index 1fad7b57a8..f614cf815c 100644 --- a/AntennaTracker/defines.h +++ b/AntennaTracker/defines.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once // Command/Waypoint/Location Options Bitmask diff --git a/AntennaTracker/radio.cpp b/AntennaTracker/radio.cpp index 0bf301a588..65bd5691c8 100644 --- a/AntennaTracker/radio.cpp +++ b/AntennaTracker/radio.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Tracker.h" // Functions to read the RC radio input diff --git a/AntennaTracker/sensors.cpp b/AntennaTracker/sensors.cpp index 889a44e780..e0a9282f98 100644 --- a/AntennaTracker/sensors.cpp +++ b/AntennaTracker/sensors.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Tracker.h" void Tracker::init_barometer(bool full_calibration) diff --git a/AntennaTracker/servos.cpp b/AntennaTracker/servos.cpp index b48c1bb76f..9c344f5638 100644 --- a/AntennaTracker/servos.cpp +++ b/AntennaTracker/servos.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Tracker.h" /* diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index 0d9877315e..d016dd10da 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Tracker.h" #include "version.h" diff --git a/AntennaTracker/tracking.cpp b/AntennaTracker/tracking.cpp index 691423d976..57cd2d1d18 100644 --- a/AntennaTracker/tracking.cpp +++ b/AntennaTracker/tracking.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Tracker.h" /** diff --git a/ArduCopter/APM_Config.h b/ArduCopter/APM_Config.h index 173623fed3..22efb269e9 100644 --- a/ArduCopter/APM_Config.h +++ b/ArduCopter/APM_Config.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // User specific config file. Any items listed in config.h can be overridden here. // If you used to define your CONFIG_APM_HARDWARE setting here, it is no longer diff --git a/ArduCopter/APM_Config_mavlink_hil.h b/ArduCopter/APM_Config_mavlink_hil.h index 094874b106..dad432892d 100644 --- a/ArduCopter/APM_Config_mavlink_hil.h +++ b/ArduCopter/APM_Config_mavlink_hil.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // HIL_MODE SELECTION // // Mavlink supports diff --git a/ArduCopter/AP_Rally.cpp b/ArduCopter/AP_Rally.cpp index c5ad504355..22e0d59333 100644 --- a/ArduCopter/AP_Rally.cpp +++ b/ArduCopter/AP_Rally.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/ArduCopter/AP_Rally.h b/ArduCopter/AP_Rally.h index 0e6a3ad19e..dace66f48a 100644 --- a/ArduCopter/AP_Rally.h +++ b/ArduCopter/AP_Rally.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/ArduCopter/AP_State.cpp b/ArduCopter/AP_State.cpp index 6cbd9451c0..d0c38b6987 100644 --- a/ArduCopter/AP_State.cpp +++ b/ArduCopter/AP_State.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // set_home_state - update home state diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index a226dc252f..8b8a45d1fa 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/ArduCopter/Attitude.cpp b/ArduCopter/Attitude.cpp index f25e5fa972..4c42f76cc2 100644 --- a/ArduCopter/Attitude.cpp +++ b/ArduCopter/Attitude.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // get_smoothing_gain - returns smoothing gain to be passed into attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 2d87fadc7e..ad4adeda25 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 10e03b9bd5..a5ec15d813 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 2bddd74991..0e6dd2ebaa 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" #include "version.h" diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 39189726de..407211b775 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" #include "version.h" diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 3529053688..636281e318 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index b556199e69..314615136f 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/ArduCopter/UserCode.cpp b/ArduCopter/UserCode.cpp index e7d2ef9d84..8611be31b4 100644 --- a/ArduCopter/UserCode.cpp +++ b/ArduCopter/UserCode.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" #ifdef USERHOOK_INIT diff --git a/ArduCopter/UserVariables.h b/ArduCopter/UserVariables.h index 6f596218ed..cdd02093d2 100644 --- a/ArduCopter/UserVariables.h +++ b/ArduCopter/UserVariables.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // user defined variables // example variables used in Wii camera testing - replace with your own diff --git a/ArduCopter/afs_copter.cpp b/ArduCopter/afs_copter.cpp index 20208133ca..278bc36769 100644 --- a/ArduCopter/afs_copter.cpp +++ b/ArduCopter/afs_copter.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* copter specific AP_AdvancedFailsafe class */ diff --git a/ArduCopter/afs_copter.h b/ArduCopter/afs_copter.h index 1279ae5229..1f64993415 100644 --- a/ArduCopter/afs_copter.h +++ b/ArduCopter/afs_copter.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/ArduCopter/arming_checks.cpp b/ArduCopter/arming_checks.cpp index bbdf7cad3e..ba9400ecc3 100644 --- a/ArduCopter/arming_checks.cpp +++ b/ArduCopter/arming_checks.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // performs pre-arm checks. expects to be called at 1hz. diff --git a/ArduCopter/baro_ground_effect.cpp b/ArduCopter/baro_ground_effect.cpp index 4861c6fa6e..427f20870d 100644 --- a/ArduCopter/baro_ground_effect.cpp +++ b/ArduCopter/baro_ground_effect.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" void Copter::update_ground_effect_detector(void) diff --git a/ArduCopter/capabilities.cpp b/ArduCopter/capabilities.cpp index f3ba3cf992..82db1897b9 100644 --- a/ArduCopter/capabilities.cpp +++ b/ArduCopter/capabilities.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" void Copter::init_capabilities(void) diff --git a/ArduCopter/commands.cpp b/ArduCopter/commands.cpp index 1ba3ed515a..91dfb67684 100644 --- a/ArduCopter/commands.cpp +++ b/ArduCopter/commands.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/commands_logic.cpp b/ArduCopter/commands_logic.cpp index 10b208c655..a329be9f81 100644 --- a/ArduCopter/commands_logic.cpp +++ b/ArduCopter/commands_logic.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // start_command - this function will be called when the ap_mission lib wishes to start a new command diff --git a/ArduCopter/compassmot.cpp b/ArduCopter/compassmot.cpp index f65c7fc757..87f55710b1 100644 --- a/ArduCopter/compassmot.cpp +++ b/ArduCopter/compassmot.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/config.h b/ArduCopter/config.h index a336b8a39d..59974c4073 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // #pragma once diff --git a/ArduCopter/control_acro.cpp b/ArduCopter/control_acro.cpp index 40b90913f8..fa1c2f9b0a 100644 --- a/ArduCopter/control_acro.cpp +++ b/ArduCopter/control_acro.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include "Copter.h" diff --git a/ArduCopter/control_althold.cpp b/ArduCopter/control_althold.cpp index cf6872aebe..1907df2c4e 100644 --- a/ArduCopter/control_althold.cpp +++ b/ArduCopter/control_althold.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include "Copter.h" diff --git a/ArduCopter/control_auto.cpp b/ArduCopter/control_auto.cpp index 7063677cf3..37e139ee0a 100644 --- a/ArduCopter/control_auto.cpp +++ b/ArduCopter/control_auto.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/control_autotune.cpp b/ArduCopter/control_autotune.cpp index 765f8fbabc..be1d2c7034 100644 --- a/ArduCopter/control_autotune.cpp +++ b/ArduCopter/control_autotune.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" #if AUTOTUNE_ENABLED == ENABLED diff --git a/ArduCopter/control_avoid_adsb.cpp b/ArduCopter/control_avoid_adsb.cpp index 0fccbe398b..1dcdeb0597 100644 --- a/ArduCopter/control_avoid_adsb.cpp +++ b/ArduCopter/control_avoid_adsb.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/control_brake.cpp b/ArduCopter/control_brake.cpp index 6b46533867..6106a86cb5 100644 --- a/ArduCopter/control_brake.cpp +++ b/ArduCopter/control_brake.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/control_circle.cpp b/ArduCopter/control_circle.cpp index 1c5122754e..2785c158df 100644 --- a/ArduCopter/control_circle.cpp +++ b/ArduCopter/control_circle.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/control_drift.cpp b/ArduCopter/control_drift.cpp index e70fefc533..14dea0eda9 100644 --- a/ArduCopter/control_drift.cpp +++ b/ArduCopter/control_drift.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/control_flip.cpp b/ArduCopter/control_flip.cpp index 0f4dd68dd6..0c8cd6dd09 100644 --- a/ArduCopter/control_flip.cpp +++ b/ArduCopter/control_flip.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/control_guided.cpp b/ArduCopter/control_guided.cpp index 6c90605d73..f47d7fa209 100644 --- a/ArduCopter/control_guided.cpp +++ b/ArduCopter/control_guided.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/control_guided_nogps.cpp b/ArduCopter/control_guided_nogps.cpp index 5f6a70b1fe..a56785c94f 100644 --- a/ArduCopter/control_guided_nogps.cpp +++ b/ArduCopter/control_guided_nogps.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/control_land.cpp b/ArduCopter/control_land.cpp index 758d07e3e4..508fa52f63 100644 --- a/ArduCopter/control_land.cpp +++ b/ArduCopter/control_land.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" static bool land_with_gps; diff --git a/ArduCopter/control_loiter.cpp b/ArduCopter/control_loiter.cpp index c34f7c3518..2bbff1adaf 100644 --- a/ArduCopter/control_loiter.cpp +++ b/ArduCopter/control_loiter.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/control_poshold.cpp b/ArduCopter/control_poshold.cpp index e7277aaa95..b68d2640b6 100644 --- a/ArduCopter/control_poshold.cpp +++ b/ArduCopter/control_poshold.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" #if POSHOLD_ENABLED == ENABLED diff --git a/ArduCopter/control_rtl.cpp b/ArduCopter/control_rtl.cpp index 7932eb246e..6fa7e9e1eb 100644 --- a/ArduCopter/control_rtl.cpp +++ b/ArduCopter/control_rtl.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/control_sport.cpp b/ArduCopter/control_sport.cpp index 762a0be598..7bd5c8eef2 100644 --- a/ArduCopter/control_sport.cpp +++ b/ArduCopter/control_sport.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/control_stabilize.cpp b/ArduCopter/control_stabilize.cpp index 0037e1ddc1..7e9ea86bf4 100644 --- a/ArduCopter/control_stabilize.cpp +++ b/ArduCopter/control_stabilize.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/control_throw.cpp b/ArduCopter/control_throw.cpp index 537ac1932f..8192b0fb66 100644 --- a/ArduCopter/control_throw.cpp +++ b/ArduCopter/control_throw.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" diff --git a/ArduCopter/crash_check.cpp b/ArduCopter/crash_check.cpp index 01d164e608..0ff358d44a 100644 --- a/ArduCopter/crash_check.cpp +++ b/ArduCopter/crash_check.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // Code to detect a crash main ArduCopter code diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index 6a86ee82ce..0937ab65ba 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/ArduCopter/ekf_check.cpp b/ArduCopter/ekf_check.cpp index 21393e0f08..5a20710303 100644 --- a/ArduCopter/ekf_check.cpp +++ b/ArduCopter/ekf_check.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /** diff --git a/ArduCopter/esc_calibration.cpp b/ArduCopter/esc_calibration.cpp index e971f1b0dc..dc083c7f02 100644 --- a/ArduCopter/esc_calibration.cpp +++ b/ArduCopter/esc_calibration.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /***************************************************************************** diff --git a/ArduCopter/events.cpp b/ArduCopter/events.cpp index 5783e1869b..2a713e61c4 100644 --- a/ArduCopter/events.cpp +++ b/ArduCopter/events.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/failsafe.cpp b/ArduCopter/failsafe.cpp index 0a8951d201..09b5623d79 100644 --- a/ArduCopter/failsafe.cpp +++ b/ArduCopter/failsafe.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // diff --git a/ArduCopter/fence.cpp b/ArduCopter/fence.cpp index 23c6a3bfed..067912bf6a 100644 --- a/ArduCopter/fence.cpp +++ b/ArduCopter/fence.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // Code to integrate AC_Fence library with main ArduCopter code diff --git a/ArduCopter/flight_mode.cpp b/ArduCopter/flight_mode.cpp index 330ca5793f..9e7b3de2a0 100644 --- a/ArduCopter/flight_mode.cpp +++ b/ArduCopter/flight_mode.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/heli.cpp b/ArduCopter/heli.cpp index 2b6ecdc073..b8c90746d7 100644 --- a/ArduCopter/heli.cpp +++ b/ArduCopter/heli.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // Traditional helicopter variables and functions diff --git a/ArduCopter/heli_control_acro.cpp b/ArduCopter/heli_control_acro.cpp index 6eaa672b3c..40f5f95d95 100644 --- a/ArduCopter/heli_control_acro.cpp +++ b/ArduCopter/heli_control_acro.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" #if FRAME_CONFIG == HELI_FRAME diff --git a/ArduCopter/heli_control_stabilize.cpp b/ArduCopter/heli_control_stabilize.cpp index 3c17f77b77..f1f1aadc77 100644 --- a/ArduCopter/heli_control_stabilize.cpp +++ b/ArduCopter/heli_control_stabilize.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" #if FRAME_CONFIG == HELI_FRAME diff --git a/ArduCopter/inertia.cpp b/ArduCopter/inertia.cpp index e930b83368..2b180ff773 100644 --- a/ArduCopter/inertia.cpp +++ b/ArduCopter/inertia.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // read_inertia - read inertia in from accelerometers diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index b220aebc51..3c347ea19a 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // Code to detect a crash main ArduCopter code diff --git a/ArduCopter/landing_gear.cpp b/ArduCopter/landing_gear.cpp index c31ac83ae4..ab7267e4d8 100644 --- a/ArduCopter/landing_gear.cpp +++ b/ArduCopter/landing_gear.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" diff --git a/ArduCopter/leds.cpp b/ArduCopter/leds.cpp index f36b0bbebd..38f65998ae 100644 --- a/ArduCopter/leds.cpp +++ b/ArduCopter/leds.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" diff --git a/ArduCopter/motor_test.cpp b/ArduCopter/motor_test.cpp index 8b23f21024..097d18d4f7 100644 --- a/ArduCopter/motor_test.cpp +++ b/ArduCopter/motor_test.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduCopter/motors.cpp b/ArduCopter/motors.cpp index a649740488..05b75c1096 100644 --- a/ArduCopter/motors.cpp +++ b/ArduCopter/motors.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" #define ARM_DELAY 20 // called at 10hz so 2 seconds diff --git a/ArduCopter/navigation.cpp b/ArduCopter/navigation.cpp index a2dcaa96ed..4c50e27e90 100644 --- a/ArduCopter/navigation.cpp +++ b/ArduCopter/navigation.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // run_nav_updates - top level call for the autopilot diff --git a/ArduCopter/perf_info.cpp b/ArduCopter/perf_info.cpp index e6d499c999..beacec292a 100644 --- a/ArduCopter/perf_info.cpp +++ b/ArduCopter/perf_info.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // diff --git a/ArduCopter/position_vector.cpp b/ArduCopter/position_vector.cpp index 1c292f5595..af999f123c 100644 --- a/ArduCopter/position_vector.cpp +++ b/ArduCopter/position_vector.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // Position vectors related utility functions diff --git a/ArduCopter/precision_landing.cpp b/ArduCopter/precision_landing.cpp index b377bd9075..aff44d2a78 100644 --- a/ArduCopter/precision_landing.cpp +++ b/ArduCopter/precision_landing.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // // functions to support precision landing // diff --git a/ArduCopter/radio.cpp b/ArduCopter/radio.cpp index 2201ff7d1e..3370551c2b 100644 --- a/ArduCopter/radio.cpp +++ b/ArduCopter/radio.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index dd94d9888b..1e989a8552 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" void Copter::init_barometer(bool full_calibration) diff --git a/ArduCopter/setup.cpp b/ArduCopter/setup.cpp index 96f80ff1fb..6cc895f981 100644 --- a/ArduCopter/setup.cpp +++ b/ArduCopter/setup.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" #if CLI_ENABLED == ENABLED diff --git a/ArduCopter/switches.cpp b/ArduCopter/switches.cpp index 55dbb67413..0440708dbe 100644 --- a/ArduCopter/switches.cpp +++ b/ArduCopter/switches.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" #define CONTROL_SWITCH_DEBOUNCE_TIME_MS 200 diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 418256a15d..60f6a48651 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" #include "version.h" diff --git a/ArduCopter/takeoff.cpp b/ArduCopter/takeoff.cpp index 4c5cdc4439..ac266fc90f 100644 --- a/ArduCopter/takeoff.cpp +++ b/ArduCopter/takeoff.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // This file contains the high-level takeoff logic for Loiter, PosHold, AltHold, Sport modes. diff --git a/ArduCopter/terrain.cpp b/ArduCopter/terrain.cpp index 2a93d0ee3f..a034c449a4 100644 --- a/ArduCopter/terrain.cpp +++ b/ArduCopter/terrain.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" // update terrain data diff --git a/ArduCopter/test.cpp b/ArduCopter/test.cpp index 043d5915d3..bca4e20d1b 100644 --- a/ArduCopter/test.cpp +++ b/ArduCopter/test.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" #if CLI_ENABLED == ENABLED diff --git a/ArduCopter/tuning.cpp b/ArduCopter/tuning.cpp index 4d66159e03..06b3d86765 100644 --- a/ArduCopter/tuning.cpp +++ b/ArduCopter/tuning.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Copter.h" /* diff --git a/ArduPlane/APM_Config.h b/ArduPlane/APM_Config.h index f2ef2609a8..907fbc4411 100644 --- a/ArduPlane/APM_Config.h +++ b/ArduPlane/APM_Config.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // This file is just a placeholder for your configuration file. If // you wish to change any of the setup parameters from their default // values, place the appropriate #define statements here. diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 39e6547ad8..f4eaac97f1 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* Lead developer: Andrew Tridgell diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 338cd75aac..64682cd6c1 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" /* diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index d249b7d3b2..ae0265985b 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "GCS_Mavlink.h" #include "Plane.h" diff --git a/ArduPlane/Log.cpp b/ArduPlane/Log.cpp index b50820c16a..0987173abd 100644 --- a/ArduPlane/Log.cpp +++ b/ArduPlane/Log.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" #include "version.h" diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 5f5dab871b..0aee30caac 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" /* diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 0407c99786..58d8b551ec 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/ArduPlane/Plane.cpp b/ArduPlane/Plane.cpp index 8d0e9bdfac..2c594dd2f9 100644 --- a/ArduPlane/Plane.cpp +++ b/ArduPlane/Plane.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 92a123d1f1..6a77398d05 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* Lead developer: Andrew Tridgell & Tom Pittenger diff --git a/ArduPlane/afs_plane.cpp b/ArduPlane/afs_plane.cpp index 2b2b383f83..13f5de0f19 100644 --- a/ArduPlane/afs_plane.cpp +++ b/ArduPlane/afs_plane.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* plane specific AP_AdvancedFailsafe class */ diff --git a/ArduPlane/altitude.cpp b/ArduPlane/altitude.cpp index 71077d8be8..4e5bfa212a 100644 --- a/ArduPlane/altitude.cpp +++ b/ArduPlane/altitude.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/ArduPlane/arming_checks.cpp b/ArduPlane/arming_checks.cpp index 923d78f99e..e3e7c4148a 100644 --- a/ArduPlane/arming_checks.cpp +++ b/ArduPlane/arming_checks.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* additional arming checks for plane */ diff --git a/ArduPlane/capabilities.cpp b/ArduPlane/capabilities.cpp index 68da406fb0..54872663ba 100644 --- a/ArduPlane/capabilities.cpp +++ b/ArduPlane/capabilities.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" void Plane::init_capabilities(void) diff --git a/ArduPlane/commands.cpp b/ArduPlane/commands.cpp index f896ca3a44..496170d233 100644 --- a/ArduPlane/commands.cpp +++ b/ArduPlane/commands.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * logic for dealing with the current command in the mission and home location */ diff --git a/ArduPlane/commands_logic.cpp b/ArduPlane/commands_logic.cpp index cc256ab2c9..28c141e57b 100644 --- a/ArduPlane/commands_logic.cpp +++ b/ArduPlane/commands_logic.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" /********************************************************************************/ diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 83803974b0..4411078c7e 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduPlane/control_modes.cpp b/ArduPlane/control_modes.cpp index b6eef78c64..1bff875390 100644 --- a/ArduPlane/control_modes.cpp +++ b/ArduPlane/control_modes.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" void Plane::read_control_switch() diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index a4259a7f1c..48e4f5970d 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once // Internal defines, don't edit and expect things to work diff --git a/ArduPlane/events.cpp b/ArduPlane/events.cpp index 4ce0262b5d..0fcbd410ee 100644 --- a/ArduPlane/events.cpp +++ b/ArduPlane/events.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" void Plane::failsafe_short_on_event(enum failsafe_state fstype, mode_reason_t reason) diff --git a/ArduPlane/failsafe.cpp b/ArduPlane/failsafe.cpp index 620fd59e06..b6185e4e42 100644 --- a/ArduPlane/failsafe.cpp +++ b/ArduPlane/failsafe.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" /* diff --git a/ArduPlane/geofence.cpp b/ArduPlane/geofence.cpp index fce453f343..a4b3b69b92 100644 --- a/ArduPlane/geofence.cpp +++ b/ArduPlane/geofence.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * geo-fencing support * Andrew Tridgell, December 2011 diff --git a/ArduPlane/is_flying.cpp b/ArduPlane/is_flying.cpp index 1561cad5b7..34e7451dbc 100644 --- a/ArduPlane/is_flying.cpp +++ b/ArduPlane/is_flying.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" /* diff --git a/ArduPlane/landing.cpp b/ArduPlane/landing.cpp index 34aacca92d..befaf8002d 100644 --- a/ArduPlane/landing.cpp +++ b/ArduPlane/landing.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" /* diff --git a/ArduPlane/motor_test.cpp b/ArduPlane/motor_test.cpp index d5866772ff..a139a0856b 100644 --- a/ArduPlane/motor_test.cpp +++ b/ArduPlane/motor_test.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" /* diff --git a/ArduPlane/navigation.cpp b/ArduPlane/navigation.cpp index 1f006444a1..d1e1166d88 100644 --- a/ArduPlane/navigation.cpp +++ b/ArduPlane/navigation.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" // set the nav_controller pointer to the right controller diff --git a/ArduPlane/parachute.cpp b/ArduPlane/parachute.cpp index 9914ac0a97..d1cd8a4fc1 100644 --- a/ArduPlane/parachute.cpp +++ b/ArduPlane/parachute.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" diff --git a/ArduPlane/px4_mixer.cpp b/ArduPlane/px4_mixer.cpp index d7b9ccc0a9..7f983b85fa 100644 --- a/ArduPlane/px4_mixer.cpp +++ b/ArduPlane/px4_mixer.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" /* diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 417522b62b..48fbf36ac2 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" const AP_Param::GroupInfo QuadPlane::var_info[] = { diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index af7a0cdde3..0c44e9ed5f 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include #include // Attitude control library diff --git a/ArduPlane/radio.cpp b/ArduPlane/radio.cpp index 0d3075ff6e..e0e5a7dd3a 100644 --- a/ArduPlane/radio.cpp +++ b/ArduPlane/radio.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" //Function that will read the radio data, limit servos and trigger a failsafe diff --git a/ArduPlane/sensors.cpp b/ArduPlane/sensors.cpp index e6475eb7b8..2503216bd7 100644 --- a/ArduPlane/sensors.cpp +++ b/ArduPlane/sensors.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" #include diff --git a/ArduPlane/servos.cpp b/ArduPlane/servos.cpp index d337d84129..8cc75575bb 100644 --- a/ArduPlane/servos.cpp +++ b/ArduPlane/servos.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/ArduPlane/setup.cpp b/ArduPlane/setup.cpp index f57ff994c8..8199a18c25 100644 --- a/ArduPlane/setup.cpp +++ b/ArduPlane/setup.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" #if CLI_ENABLED == ENABLED diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 61901c0a34..e319ac3db9 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" #include "version.h" diff --git a/ArduPlane/takeoff.cpp b/ArduPlane/takeoff.cpp index 9581f810b0..b68cee7189 100644 --- a/ArduPlane/takeoff.cpp +++ b/ArduPlane/takeoff.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" /* Check for automatic takeoff conditions being met using the following sequence: diff --git a/ArduPlane/test.cpp b/ArduPlane/test.cpp index 0886f71e9e..a8a19edc8f 100644 --- a/ArduPlane/test.cpp +++ b/ArduPlane/test.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" #if CLI_ENABLED == ENABLED diff --git a/ArduPlane/tiltrotor.cpp b/ArduPlane/tiltrotor.cpp index ff2ff37a99..316c914d75 100644 --- a/ArduPlane/tiltrotor.cpp +++ b/ArduPlane/tiltrotor.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" /* diff --git a/ArduPlane/tuning.cpp b/ArduPlane/tuning.cpp index b6947d8bf1..ed8027a9b6 100644 --- a/ArduPlane/tuning.cpp +++ b/ArduPlane/tuning.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "Plane.h" /* diff --git a/ArduPlane/tuning.h b/ArduPlane/tuning.h index 61009e4884..b73c37e2e2 100644 --- a/ArduPlane/tuning.h +++ b/ArduPlane/tuning.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include /* diff --git a/Tools/CPUInfo/CPUInfo.cpp b/Tools/CPUInfo/CPUInfo.cpp index 6719ebcb10..838da0d39e 100644 --- a/Tools/CPUInfo/CPUInfo.cpp +++ b/Tools/CPUInfo/CPUInfo.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* test CPU speed Andrew Tridgell September 2011 diff --git a/Tools/Hello/Hello.cpp b/Tools/Hello/Hello.cpp index 45da7afbec..ab0fcadfda 100644 --- a/Tools/Hello/Hello.cpp +++ b/Tools/Hello/Hello.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* simple hello world sketch Andrew Tridgell September 2011 diff --git a/Tools/Replay/Parameters.h b/Tools/Replay/Parameters.h index 2e2653437d..4a89c73ae2 100644 --- a/Tools/Replay/Parameters.h +++ b/Tools/Replay/Parameters.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/Tools/Replay/Replay.cpp b/Tools/Replay/Replay.cpp index a58d054321..778e53bbd3 100644 --- a/Tools/Replay/Replay.cpp +++ b/Tools/Replay/Replay.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/Tools/Replay/Replay.h b/Tools/Replay/Replay.h index 1dac146f56..bb0a5bf646 100644 --- a/Tools/Replay/Replay.h +++ b/Tools/Replay/Replay.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp index 3d50f1b81c..bd92f261b4 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "AC_AttitudeControl.h" #include #include diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 4130f16539..28c6d92fd3 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once /// @file AC_AttitudeControl.h diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp index 03f5e86b87..1e2f049b05 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- - #include "AC_AttitudeControl_Heli.h" #include diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h index 3c93348a54..f26b7b1347 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- #pragma once /// @file AC_AttitudeControl_Heli.h diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index 68788bf9bb..3d5d26845d 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- - #include "AC_AttitudeControl_Multi.h" #include #include diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h index ca2959dd02..95246122e3 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- #pragma once /// @file AC_AttitudeControl_Multi.h diff --git a/libraries/AC_AttitudeControl/AC_PosControl.cpp b/libraries/AC_AttitudeControl/AC_PosControl.cpp index 8ea033d49b..e880c14f63 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.cpp +++ b/libraries/AC_AttitudeControl/AC_PosControl.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #include "AC_PosControl.h" #include diff --git a/libraries/AC_AttitudeControl/AC_PosControl.h b/libraries/AC_AttitudeControl/AC_PosControl.h index 318e833104..929db493d8 100644 --- a/libraries/AC_AttitudeControl/AC_PosControl.h +++ b/libraries/AC_AttitudeControl/AC_PosControl.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AC_AttitudeControl/ControlMonitor.cpp b/libraries/AC_AttitudeControl/ControlMonitor.cpp index 0eeeb11c79..45598618b0 100644 --- a/libraries/AC_AttitudeControl/ControlMonitor.cpp +++ b/libraries/AC_AttitudeControl/ControlMonitor.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "AC_AttitudeControl.h" #include #include diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index e4f914ba52..17b1dfecf2 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #include "AC_Fence.h" #include diff --git a/libraries/AC_Fence/AC_Fence.h b/libraries/AC_Fence/AC_Fence.h index 5395482c80..ede920cdf5 100644 --- a/libraries/AC_Fence/AC_Fence.h +++ b/libraries/AC_Fence/AC_Fence.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AC_InputManager/AC_InputManager.cpp b/libraries/AC_InputManager/AC_InputManager.cpp index db12615c02..67744587ab 100644 --- a/libraries/AC_InputManager/AC_InputManager.cpp +++ b/libraries/AC_InputManager/AC_InputManager.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "AC_InputManager.h" #include #include diff --git a/libraries/AC_InputManager/AC_InputManager.h b/libraries/AC_InputManager/AC_InputManager.h index a30033ddd2..79f4cb92f1 100644 --- a/libraries/AC_InputManager/AC_InputManager.h +++ b/libraries/AC_InputManager/AC_InputManager.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once /// @file AC_InputManager.h diff --git a/libraries/AC_InputManager/AC_InputManager_Heli.cpp b/libraries/AC_InputManager/AC_InputManager_Heli.cpp index 714b27e9af..8262cdfa8e 100644 --- a/libraries/AC_InputManager/AC_InputManager_Heli.cpp +++ b/libraries/AC_InputManager/AC_InputManager_Heli.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "AC_InputManager_Heli.h" #include #include diff --git a/libraries/AC_InputManager/AC_InputManager_Heli.h b/libraries/AC_InputManager/AC_InputManager_Heli.h index 3c6ccabd27..9dc68fce63 100644 --- a/libraries/AC_InputManager/AC_InputManager_Heli.h +++ b/libraries/AC_InputManager/AC_InputManager_Heli.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once /// @file AC_InputManager_Heli.h diff --git a/libraries/AC_PID/AC_HELI_PID.cpp b/libraries/AC_PID/AC_HELI_PID.cpp index 3818b66515..cf0cf5cdb9 100644 --- a/libraries/AC_PID/AC_HELI_PID.cpp +++ b/libraries/AC_PID/AC_HELI_PID.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AC_HELI_PID.cpp /// @brief Generic PID algorithm diff --git a/libraries/AC_PID/AC_HELI_PID.h b/libraries/AC_PID/AC_HELI_PID.h index d44e37d502..0e66db608a 100644 --- a/libraries/AC_PID/AC_HELI_PID.h +++ b/libraries/AC_PID/AC_HELI_PID.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once /// @file AC_HELI_PID.h diff --git a/libraries/AC_PID/AC_P.cpp b/libraries/AC_PID/AC_P.cpp index 2b6a29d364..10e53178a0 100644 --- a/libraries/AC_PID/AC_P.cpp +++ b/libraries/AC_PID/AC_P.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AC_P.cpp /// @brief Generic P algorithm diff --git a/libraries/AC_PID/AC_P.h b/libraries/AC_PID/AC_P.h index 09d0252fd3..8b665fc439 100644 --- a/libraries/AC_PID/AC_P.h +++ b/libraries/AC_PID/AC_P.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once /// @file AC_PD.h diff --git a/libraries/AC_PID/AC_PID.cpp b/libraries/AC_PID/AC_PID.cpp index 3431d98ae8..ff1c0c178f 100644 --- a/libraries/AC_PID/AC_PID.cpp +++ b/libraries/AC_PID/AC_PID.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AC_PID.cpp /// @brief Generic PID algorithm diff --git a/libraries/AC_PID/AC_PID.h b/libraries/AC_PID/AC_PID.h index d511fcfe4a..bb1ae2d3b4 100644 --- a/libraries/AC_PID/AC_PID.h +++ b/libraries/AC_PID/AC_PID.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once /// @file AC_PID.h diff --git a/libraries/AC_PID/AC_PI_2D.cpp b/libraries/AC_PID/AC_PI_2D.cpp index 68aa15bb80..900c207f7b 100644 --- a/libraries/AC_PID/AC_PI_2D.cpp +++ b/libraries/AC_PID/AC_PI_2D.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AC_PI_2D.cpp /// @brief Generic PID algorithm diff --git a/libraries/AC_PID/AC_PI_2D.h b/libraries/AC_PID/AC_PI_2D.h index c0632e08e3..057f312a76 100644 --- a/libraries/AC_PID/AC_PI_2D.h +++ b/libraries/AC_PID/AC_PI_2D.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once /// @file AC_PI_2D.h diff --git a/libraries/AC_PrecLand/AC_PrecLand.cpp b/libraries/AC_PrecLand/AC_PrecLand.cpp index 9b4cc70ce1..35bbe0d39d 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #include "AC_PrecLand.h" #include "AC_PrecLand_Backend.h" diff --git a/libraries/AC_PrecLand/AC_PrecLand.h b/libraries/AC_PrecLand/AC_PrecLand.h index cc1671e420..f759a67917 100644 --- a/libraries/AC_PrecLand/AC_PrecLand.h +++ b/libraries/AC_PrecLand/AC_PrecLand.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AC_PrecLand/AC_PrecLand_Backend.h b/libraries/AC_PrecLand/AC_PrecLand_Backend.h index 6cdc422417..ee0782d7ea 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Backend.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Backend.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp index 5232b54435..e104425160 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #include "AC_PrecLand_Companion.h" diff --git a/libraries/AC_PrecLand/AC_PrecLand_Companion.h b/libraries/AC_PrecLand/AC_PrecLand_Companion.h index 9c108f90e1..61e81f2728 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_Companion.h +++ b/libraries/AC_PrecLand/AC_PrecLand_Companion.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp index f0fac086fb..5d3c17a56b 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #include "AC_PrecLand_IRLock.h" diff --git a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h index f8e783cc39..b6718f5dd1 100644 --- a/libraries/AC_PrecLand/AC_PrecLand_IRLock.h +++ b/libraries/AC_PrecLand/AC_PrecLand_IRLock.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AC_PrecLand/PosVelEKF.h b/libraries/AC_PrecLand/PosVelEKF.h index 5ef2fa3a73..a769abd9e7 100644 --- a/libraries/AC_PrecLand/PosVelEKF.h +++ b/libraries/AC_PrecLand/PosVelEKF.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once class PosVelEKF { diff --git a/libraries/AC_Sprayer/AC_Sprayer.cpp b/libraries/AC_Sprayer/AC_Sprayer.cpp index 9beb23ce5f..be25b2445c 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.cpp +++ b/libraries/AC_Sprayer/AC_Sprayer.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include "AC_Sprayer.h" diff --git a/libraries/AC_Sprayer/AC_Sprayer.h b/libraries/AC_Sprayer/AC_Sprayer.h index 524c93dd0f..5673c1d82f 100644 --- a/libraries/AC_Sprayer/AC_Sprayer.h +++ b/libraries/AC_Sprayer/AC_Sprayer.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AC_Sprayer.h /// @brief Crop sprayer library diff --git a/libraries/AC_WPNav/AC_Circle.cpp b/libraries/AC_WPNav/AC_Circle.cpp index 61497c503b..7658ac25da 100644 --- a/libraries/AC_WPNav/AC_Circle.cpp +++ b/libraries/AC_WPNav/AC_Circle.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #include "AC_Circle.h" #include diff --git a/libraries/AC_WPNav/AC_Circle.h b/libraries/AC_WPNav/AC_Circle.h index cde396c3b1..21fad2f9f9 100644 --- a/libraries/AC_WPNav/AC_Circle.h +++ b/libraries/AC_WPNav/AC_Circle.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AC_WPNav/AC_WPNav.cpp b/libraries/AC_WPNav/AC_WPNav.cpp index 1f5582a18a..f62d66d3b9 100644 --- a/libraries/AC_WPNav/AC_WPNav.cpp +++ b/libraries/AC_WPNav/AC_WPNav.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #include "AC_WPNav.h" diff --git a/libraries/AC_WPNav/AC_WPNav.h b/libraries/AC_WPNav/AC_WPNav.h index 8f5b33e7d9..3059f0e185 100644 --- a/libraries/AC_WPNav/AC_WPNav.h +++ b/libraries/AC_WPNav/AC_WPNav.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/APM_Control/AP_AutoTune.cpp b/libraries/APM_Control/AP_AutoTune.cpp index 546255d34e..472cf05477 100644 --- a/libraries/APM_Control/AP_AutoTune.cpp +++ b/libraries/APM_Control/AP_AutoTune.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/APM_Control/AP_AutoTune.h b/libraries/APM_Control/AP_AutoTune.h index 724c483610..62175fd5cf 100644 --- a/libraries/APM_Control/AP_AutoTune.h +++ b/libraries/APM_Control/AP_AutoTune.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/APM_Control/AP_PitchController.cpp b/libraries/APM_Control/AP_PitchController.cpp index 06a4f9c406..edea749962 100644 --- a/libraries/APM_Control/AP_PitchController.cpp +++ b/libraries/APM_Control/AP_PitchController.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/APM_Control/AP_PitchController.h b/libraries/APM_Control/AP_PitchController.h index 7cdac2d63f..921a6a3e49 100644 --- a/libraries/APM_Control/AP_PitchController.h +++ b/libraries/APM_Control/AP_PitchController.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/APM_Control/AP_RollController.cpp b/libraries/APM_Control/AP_RollController.cpp index a770df83b9..8c4741dca8 100644 --- a/libraries/APM_Control/AP_RollController.cpp +++ b/libraries/APM_Control/AP_RollController.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/APM_Control/AP_RollController.h b/libraries/APM_Control/AP_RollController.h index aea62ba053..a93926c5c9 100644 --- a/libraries/APM_Control/AP_RollController.h +++ b/libraries/APM_Control/AP_RollController.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/APM_Control/AP_SteerController.cpp b/libraries/APM_Control/AP_SteerController.cpp index 7cf34a270a..6cbd0ecabe 100644 --- a/libraries/APM_Control/AP_SteerController.cpp +++ b/libraries/APM_Control/AP_SteerController.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/APM_Control/AP_SteerController.h b/libraries/APM_Control/AP_SteerController.h index bd249d318d..44d06f4565 100644 --- a/libraries/APM_Control/AP_SteerController.h +++ b/libraries/APM_Control/AP_SteerController.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/APM_Control/AP_YawController.cpp b/libraries/APM_Control/AP_YawController.cpp index df7add4b23..ae15aa777a 100644 --- a/libraries/APM_Control/AP_YawController.cpp +++ b/libraries/APM_Control/AP_YawController.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/APM_Control/AP_YawController.h b/libraries/APM_Control/AP_YawController.h index d5e11e9143..fe25dbd832 100644 --- a/libraries/APM_Control/AP_YawController.h +++ b/libraries/APM_Control/AP_YawController.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_ADC/AP_ADC_ADS1115.h b/libraries/AP_ADC/AP_ADC_ADS1115.h index 6757258254..98e6544875 100644 --- a/libraries/AP_ADC/AP_ADC_ADS1115.h +++ b/libraries/AP_ADC/AP_ADC_ADS1115.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 2c58b12529..10e98fb1e9 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_ADSB/AP_ADSB.h b/libraries/AP_ADSB/AP_ADSB.h index fbf73b1742..7c3b8f06a0 100644 --- a/libraries/AP_ADSB/AP_ADSB.h +++ b/libraries/AP_ADSB/AP_ADSB.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once /* diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index dcddb85da5..fbf47e4792 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* APM_AHRS.cpp diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 16b23dfb8f..d4301d9eea 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once /* diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 73bb61f567..4458c89d3b 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * APM_AHRS_DCM.cpp * diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.h b/libraries/AP_AHRS/AP_AHRS_DCM.h index 05e01029e4..c5303d7c85 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.h +++ b/libraries/AP_AHRS/AP_AHRS_DCM.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once /* diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index 833ef5ff5e..833f0ef26f 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index 4a873800fd..eada0fb010 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once /* diff --git a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp index 556de33849..d347e7d15a 100644 --- a/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp +++ b/libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // // Simple test for the AP_AHRS interface // diff --git a/libraries/AP_AccelCal/AP_AccelCal.cpp b/libraries/AP_AccelCal/AP_AccelCal.cpp index a5f3e965cf..88bf6b6784 100644 --- a/libraries/AP_AccelCal/AP_AccelCal.cpp +++ b/libraries/AP_AccelCal/AP_AccelCal.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_AccelCal/AccelCalibrator.cpp b/libraries/AP_AccelCal/AccelCalibrator.cpp index bee0a72386..5712da567a 100644 --- a/libraries/AP_AccelCal/AccelCalibrator.cpp +++ b/libraries/AP_AccelCal/AccelCalibrator.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_AccelCal/AccelCalibrator.h b/libraries/AP_AccelCal/AccelCalibrator.h index 17726beb9b..976668ce21 100644 --- a/libraries/AP_AccelCal/AccelCalibrator.h +++ b/libraries/AP_AccelCal/AccelCalibrator.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp index 7e84ddbb53..88d8ba9c1b 100644 --- a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp +++ b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h index 4edfb8541f..3e11e26253 100644 --- a/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h +++ b/libraries/AP_AdvancedFailsafe/AP_AdvancedFailsafe.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once /* diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 7467c08d9b..7bbc2ddc4f 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Airspeed/AP_Airspeed.h b/libraries/AP_Airspeed/AP_Airspeed.h index f60733bc50..4248c0e067 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.h +++ b/libraries/AP_Airspeed/AP_Airspeed.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_Airspeed/AP_Airspeed_Backend.h b/libraries/AP_Airspeed/AP_Airspeed_Backend.h index 60b00b3e4a..9845adb474 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_Backend.h +++ b/libraries/AP_Airspeed/AP_Airspeed_Backend.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Airspeed/AP_Airspeed_I2C.cpp b/libraries/AP_Airspeed/AP_Airspeed_I2C.cpp index a83bb26c54..4dddd6e34d 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_I2C.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_I2C.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Airspeed/AP_Airspeed_I2C.h b/libraries/AP_Airspeed/AP_Airspeed_I2C.h index 5b9f732228..0eae1a87c6 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_I2C.h +++ b/libraries/AP_Airspeed/AP_Airspeed_I2C.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Airspeed/AP_Airspeed_PX4.cpp b/libraries/AP_Airspeed/AP_Airspeed_PX4.cpp index 6b319f5ed0..c69f5c7485 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_PX4.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_PX4.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Airspeed/AP_Airspeed_PX4.h b/libraries/AP_Airspeed/AP_Airspeed_PX4.h index e7424563af..4766920058 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_PX4.h +++ b/libraries/AP_Airspeed/AP_Airspeed_PX4.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Airspeed/AP_Airspeed_analog.cpp b/libraries/AP_Airspeed/AP_Airspeed_analog.cpp index cec9e0f639..6e723a3027 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_analog.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_analog.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Airspeed/AP_Airspeed_analog.h b/libraries/AP_Airspeed/AP_Airspeed_analog.h index 016461b4eb..b2db84fab8 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_analog.h +++ b/libraries/AP_Airspeed/AP_Airspeed_analog.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_Airspeed/Airspeed_Calibration.cpp b/libraries/AP_Airspeed/Airspeed_Calibration.cpp index 3faa6d980d..fa8aa3dede 100644 --- a/libraries/AP_Airspeed/Airspeed_Calibration.cpp +++ b/libraries/AP_Airspeed/Airspeed_Calibration.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * auto_calibration.cpp - airspeed auto calibration * diff --git a/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp b/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp index 21d9a6c46f..db9ee50c0c 100644 --- a/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp +++ b/libraries/AP_Airspeed/examples/Airspeed/Airspeed.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Arming/AP_Arming.cpp b/libraries/AP_Arming/AP_Arming.cpp index 0e4c2fa7bd..8d551ea120 100644 --- a/libraries/AP_Arming/AP_Arming.cpp +++ b/libraries/AP_Arming/AP_Arming.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Arming/AP_Arming.h b/libraries/AP_Arming/AP_Arming.h index 6818fd0ab3..d1a6157b5b 100644 --- a/libraries/AP_Arming/AP_Arming.h +++ b/libraries/AP_Arming/AP_Arming.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_Avoidance/AP_Avoidance.h b/libraries/AP_Avoidance/AP_Avoidance.h index f2d79d6fd3..84b1c05a97 100644 --- a/libraries/AP_Avoidance/AP_Avoidance.h +++ b/libraries/AP_Avoidance/AP_Avoidance.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #pragma once /* diff --git a/libraries/AP_Baro/AP_Baro.cpp b/libraries/AP_Baro/AP_Baro.cpp index 64f2626209..1008cb3bc6 100644 --- a/libraries/AP_Baro/AP_Baro.cpp +++ b/libraries/AP_Baro/AP_Baro.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Baro/AP_Baro.h b/libraries/AP_Baro/AP_Baro.h index 57eb6e6a4d..ebfc5e7ae1 100644 --- a/libraries/AP_Baro/AP_Baro.h +++ b/libraries/AP_Baro/AP_Baro.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_Baro/AP_Baro_BMP085.cpp b/libraries/AP_Baro/AP_Baro_BMP085.cpp index 50613ed039..f809e13607 100644 --- a/libraries/AP_Baro/AP_Baro_BMP085.cpp +++ b/libraries/AP_Baro/AP_Baro_BMP085.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Baro/AP_Baro_BMP085.h b/libraries/AP_Baro/AP_Baro_BMP085.h index 7af4c4d017..f8162e1519 100644 --- a/libraries/AP_Baro/AP_Baro_BMP085.h +++ b/libraries/AP_Baro/AP_Baro_BMP085.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_Baro/AP_Baro_Backend.cpp b/libraries/AP_Baro/AP_Baro_Backend.cpp index 51626b8936..8552f8367c 100644 --- a/libraries/AP_Baro/AP_Baro_Backend.cpp +++ b/libraries/AP_Baro/AP_Baro_Backend.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include "AP_Baro_Backend.h" extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_Baro/AP_Baro_Backend.h b/libraries/AP_Baro/AP_Baro_Backend.h index 7ba9a65f1c..2f14a61823 100644 --- a/libraries/AP_Baro/AP_Baro_Backend.h +++ b/libraries/AP_Baro/AP_Baro_Backend.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_Baro.h" diff --git a/libraries/AP_Baro/AP_Baro_HIL.cpp b/libraries/AP_Baro/AP_Baro_HIL.cpp index a93da1cf5f..0f4936ed1d 100644 --- a/libraries/AP_Baro/AP_Baro_HIL.cpp +++ b/libraries/AP_Baro/AP_Baro_HIL.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include "AP_Baro_HIL.h" #include diff --git a/libraries/AP_Baro/AP_Baro_HIL.h b/libraries/AP_Baro/AP_Baro_HIL.h index 6c1a33dd49..f062b88c0f 100644 --- a/libraries/AP_Baro/AP_Baro_HIL.h +++ b/libraries/AP_Baro/AP_Baro_HIL.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* dummy backend for HIL (and SITL). This doesn't actually need to do any work, as setHIL() is in the frontend diff --git a/libraries/AP_Baro/AP_Baro_MS5611.cpp b/libraries/AP_Baro/AP_Baro_MS5611.cpp index ad97232490..f25a0a43c2 100644 --- a/libraries/AP_Baro/AP_Baro_MS5611.cpp +++ b/libraries/AP_Baro/AP_Baro_MS5611.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Baro/AP_Baro_MS5611.h b/libraries/AP_Baro/AP_Baro_MS5611.h index acd790c8cf..02c586de9b 100644 --- a/libraries/AP_Baro/AP_Baro_MS5611.h +++ b/libraries/AP_Baro/AP_Baro_MS5611.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_Baro_Backend.h" diff --git a/libraries/AP_Baro/AP_Baro_PX4.cpp b/libraries/AP_Baro/AP_Baro_PX4.cpp index 62ecc96cb9..634c735217 100644 --- a/libraries/AP_Baro/AP_Baro_PX4.cpp +++ b/libraries/AP_Baro/AP_Baro_PX4.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include "AP_Baro_PX4.h" #include diff --git a/libraries/AP_Baro/AP_Baro_PX4.h b/libraries/AP_Baro/AP_Baro_PX4.h index 021310ea65..56ef58ad52 100644 --- a/libraries/AP_Baro/AP_Baro_PX4.h +++ b/libraries/AP_Baro/AP_Baro_PX4.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_Baro_Backend.h" diff --git a/libraries/AP_Baro/AP_Baro_QURT.cpp b/libraries/AP_Baro/AP_Baro_QURT.cpp index 61228f6058..1e957158d1 100644 --- a/libraries/AP_Baro/AP_Baro_QURT.cpp +++ b/libraries/AP_Baro/AP_Baro_QURT.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Baro/AP_Baro_QURT.h b/libraries/AP_Baro/AP_Baro_QURT.h index d594e3e458..e016cf7afe 100644 --- a/libraries/AP_Baro/AP_Baro_QURT.h +++ b/libraries/AP_Baro/AP_Baro_QURT.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_Baro_Backend.h" diff --git a/libraries/AP_Baro/AP_Baro_qflight.cpp b/libraries/AP_Baro/AP_Baro_qflight.cpp index 8d9f19de98..8c8459153b 100644 --- a/libraries/AP_Baro/AP_Baro_qflight.cpp +++ b/libraries/AP_Baro/AP_Baro_qflight.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT diff --git a/libraries/AP_Baro/AP_Baro_qflight.h b/libraries/AP_Baro/AP_Baro_qflight.h index ff8bcf356d..ab37957134 100644 --- a/libraries/AP_Baro/AP_Baro_qflight.h +++ b/libraries/AP_Baro/AP_Baro_qflight.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_Baro_Backend.h" diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.cpp b/libraries/AP_BattMonitor/AP_BattMonitor.cpp index 368f8f14e2..eaa375e36c 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include "AP_BattMonitor.h" #include "AP_BattMonitor_Analog.h" #include "AP_BattMonitor_SMBus.h" diff --git a/libraries/AP_BattMonitor/AP_BattMonitor.h b/libraries/AP_BattMonitor/AP_BattMonitor.h index aee19c6a3b..72b813e499 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp index e49196f010..0a079d1590 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #include #include diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.h b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.h index 95cba44989..14ef9989ef 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Analog.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Analog.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include // ArduPilot Mega Analog to Digital Converter Library diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp index ffa25c437a..4eb1d5ae9c 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h index 3778e5b8f4..78ccb5270c 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Backend.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp index 4c5728498a..78a09149c9 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.h b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.h index b400d44a41..3a2abfedcc 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_Bebop.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.h b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.h index 91ca4592ec..b522ed075c 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.cpp b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.cpp index 34933ed956..6d0f7545d7 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.cpp +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #include #include diff --git a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.h b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.h index bef51e9907..f43dfe01db 100644 --- a/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.h +++ b/libraries/AP_BattMonitor/AP_BattMonitor_SMBus_I2C.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.cpp b/libraries/AP_BoardConfig/AP_BoardConfig.cpp index c8c09e55a4..c5f5b62db5 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.cpp +++ b/libraries/AP_BoardConfig/AP_BoardConfig.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_BoardConfig/AP_BoardConfig.h b/libraries/AP_BoardConfig/AP_BoardConfig.h index 114183fb17..a2f9033275 100644 --- a/libraries/AP_BoardConfig/AP_BoardConfig.h +++ b/libraries/AP_BoardConfig/AP_BoardConfig.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_BoardConfig/px4_drivers.cpp b/libraries/AP_BoardConfig/px4_drivers.cpp index 5c48c45126..3a8aa70884 100644 --- a/libraries/AP_BoardConfig/px4_drivers.cpp +++ b/libraries/AP_BoardConfig/px4_drivers.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Buffer/AP_Buffer.h b/libraries/AP_Buffer/AP_Buffer.h index 8f02ab116f..5426989577 100644 --- a/libraries/AP_Buffer/AP_Buffer.h +++ b/libraries/AP_Buffer/AP_Buffer.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_Buffer.h /// @brief fifo (queue) buffer template class #pragma once diff --git a/libraries/AP_Button/AP_Button.cpp b/libraries/AP_Button/AP_Button.cpp index 0d2a294857..f8eeb8f53f 100644 --- a/libraries/AP_Button/AP_Button.cpp +++ b/libraries/AP_Button/AP_Button.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Button/AP_Button.h b/libraries/AP_Button/AP_Button.h index f52175a2a9..8034899613 100644 --- a/libraries/AP_Button/AP_Button.h +++ b/libraries/AP_Button/AP_Button.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Camera/AP_Camera.cpp b/libraries/AP_Camera/AP_Camera.cpp index d6bebeb65f..58575f9c2e 100644 --- a/libraries/AP_Camera/AP_Camera.cpp +++ b/libraries/AP_Camera/AP_Camera.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "AP_Camera.h" #include #include diff --git a/libraries/AP_Camera/AP_Camera.h b/libraries/AP_Camera/AP_Camera.h index 6d8bc5396b..c90eb8b3c9 100644 --- a/libraries/AP_Camera/AP_Camera.h +++ b/libraries/AP_Camera/AP_Camera.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_Camera.h /// @brief Photo or video camera manager, with EEPROM-backed storage of constants. #pragma once diff --git a/libraries/AP_Common/AP_Common.cpp b/libraries/AP_Common/AP_Common.cpp index b56838efa3..217841cb39 100644 --- a/libraries/AP_Common/AP_Common.cpp +++ b/libraries/AP_Common/AP_Common.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Common/AP_Common.h b/libraries/AP_Common/AP_Common.h index efbecfd295..cd31fc8b2d 100644 --- a/libraries/AP_Common/AP_Common.h +++ b/libraries/AP_Common/AP_Common.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Common/AP_Test.h b/libraries/AP_Common/AP_Test.h index e0a4b5af3f..77097aa3ef 100644 --- a/libraries/AP_Common/AP_Test.h +++ b/libraries/AP_Common/AP_Test.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Common/c++.cpp b/libraries/AP_Common/c++.cpp index 00ac1efd21..b9804818e8 100644 --- a/libraries/AP_Common/c++.cpp +++ b/libraries/AP_Common/c++.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // // C++ runtime support not provided by Arduino // diff --git a/libraries/AP_Common/examples/AP_Common/AP_Common.cpp b/libraries/AP_Common/examples/AP_Common/AP_Common.cpp index 5b0553a72a..386f1bda89 100644 --- a/libraries/AP_Common/examples/AP_Common/AP_Common.cpp +++ b/libraries/AP_Common/examples/AP_Common/AP_Common.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // // Unit tests for the AP_Common code // diff --git a/libraries/AP_Compass/AP_Compass.cpp b/libraries/AP_Compass/AP_Compass.cpp index 00e045f3fd..015fc06a1f 100644 --- a/libraries/AP_Compass/AP_Compass.cpp +++ b/libraries/AP_Compass/AP_Compass.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX #include diff --git a/libraries/AP_Compass/AP_Compass.h b/libraries/AP_Compass/AP_Compass.h index 8f6f1bd915..551aed5bf0 100644 --- a/libraries/AP_Compass/AP_Compass.h +++ b/libraries/AP_Compass/AP_Compass.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_Compass/AP_Compass_AK8963.cpp b/libraries/AP_Compass/AP_Compass_AK8963.cpp index 094415f5c8..2f405f8963 100644 --- a/libraries/AP_Compass/AP_Compass_AK8963.cpp +++ b/libraries/AP_Compass/AP_Compass_AK8963.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Compass/AP_Compass_AK8963.h b/libraries/AP_Compass/AP_Compass_AK8963.h index 48d9219dca..38ee06fba4 100644 --- a/libraries/AP_Compass/AP_Compass_AK8963.h +++ b/libraries/AP_Compass/AP_Compass_AK8963.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_Compass/AP_Compass_BMM150.cpp b/libraries/AP_Compass/AP_Compass_BMM150.cpp index f1c5159804..48bcfffe8c 100644 --- a/libraries/AP_Compass/AP_Compass_BMM150.cpp +++ b/libraries/AP_Compass/AP_Compass_BMM150.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_Compass/AP_Compass_BMM150.h b/libraries/AP_Compass/AP_Compass_BMM150.h index 6f5a4d6210..06866125d8 100644 --- a/libraries/AP_Compass/AP_Compass_BMM150.h +++ b/libraries/AP_Compass/AP_Compass_BMM150.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_Compass/AP_Compass_Backend.cpp b/libraries/AP_Compass/AP_Compass_Backend.cpp index e14310aaa1..8748c1ddfd 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.cpp +++ b/libraries/AP_Compass/AP_Compass_Backend.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include "AP_Compass.h" diff --git a/libraries/AP_Compass/AP_Compass_Backend.h b/libraries/AP_Compass/AP_Compass_Backend.h index a6bb3f33fa..40ba461b0a 100644 --- a/libraries/AP_Compass/AP_Compass_Backend.h +++ b/libraries/AP_Compass/AP_Compass_Backend.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Compass/AP_Compass_Calibration.cpp b/libraries/AP_Compass/AP_Compass_Calibration.cpp index b8da7070b3..98cb92f4c8 100644 --- a/libraries/AP_Compass/AP_Compass_Calibration.cpp +++ b/libraries/AP_Compass/AP_Compass_Calibration.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #include #include diff --git a/libraries/AP_Compass/AP_Compass_HIL.cpp b/libraries/AP_Compass/AP_Compass_HIL.cpp index 4bddce5585..7e1ffa4e3a 100644 --- a/libraries/AP_Compass/AP_Compass_HIL.cpp +++ b/libraries/AP_Compass/AP_Compass_HIL.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Compass/AP_Compass_HIL.h b/libraries/AP_Compass/AP_Compass_HIL.h index 60dffff518..628eb88464 100644 --- a/libraries/AP_Compass/AP_Compass_HIL.h +++ b/libraries/AP_Compass/AP_Compass_HIL.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_Compass.h" diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.cpp b/libraries/AP_Compass/AP_Compass_HMC5843.cpp index 0ecdb637d2..35dea85b87 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.cpp +++ b/libraries/AP_Compass/AP_Compass_HMC5843.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Compass/AP_Compass_HMC5843.h b/libraries/AP_Compass/AP_Compass_HMC5843.h index 2249247679..5484063373 100644 --- a/libraries/AP_Compass/AP_Compass_HMC5843.h +++ b/libraries/AP_Compass/AP_Compass_HMC5843.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_Compass/AP_Compass_LSM303D.cpp b/libraries/AP_Compass/AP_Compass_LSM303D.cpp index bc029bb2e4..a9f9b344ff 100644 --- a/libraries/AP_Compass/AP_Compass_LSM303D.cpp +++ b/libraries/AP_Compass/AP_Compass_LSM303D.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Compass/AP_Compass_LSM303D.h b/libraries/AP_Compass/AP_Compass_LSM303D.h index eaed50c7fd..3a4f986972 100644 --- a/libraries/AP_Compass/AP_Compass_LSM303D.h +++ b/libraries/AP_Compass/AP_Compass_LSM303D.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_Compass/AP_Compass_PX4.cpp b/libraries/AP_Compass/AP_Compass_PX4.cpp index d8ed469ac9..1561c8dc70 100644 --- a/libraries/AP_Compass/AP_Compass_PX4.cpp +++ b/libraries/AP_Compass/AP_Compass_PX4.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Compass/AP_Compass_PX4.h b/libraries/AP_Compass/AP_Compass_PX4.h index c39c1432ed..653bdc988e 100644 --- a/libraries/AP_Compass/AP_Compass_PX4.h +++ b/libraries/AP_Compass/AP_Compass_PX4.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_Compass.h" diff --git a/libraries/AP_Compass/AP_Compass_QURT.cpp b/libraries/AP_Compass/AP_Compass_QURT.cpp index ce3baa7dc3..79d4054eec 100644 --- a/libraries/AP_Compass/AP_Compass_QURT.cpp +++ b/libraries/AP_Compass/AP_Compass_QURT.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Compass/AP_Compass_QURT.h b/libraries/AP_Compass/AP_Compass_QURT.h index 8a0080532b..193042e7bd 100644 --- a/libraries/AP_Compass/AP_Compass_QURT.h +++ b/libraries/AP_Compass/AP_Compass_QURT.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #pragma once #include "AP_Compass.h" diff --git a/libraries/AP_Compass/AP_Compass_qflight.cpp b/libraries/AP_Compass/AP_Compass_qflight.cpp index d7232881a3..8d91c60a42 100644 --- a/libraries/AP_Compass/AP_Compass_qflight.cpp +++ b/libraries/AP_Compass/AP_Compass_qflight.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Compass/AP_Compass_qflight.h b/libraries/AP_Compass/AP_Compass_qflight.h index 015c2753f1..61fe663508 100644 --- a/libraries/AP_Compass/AP_Compass_qflight.h +++ b/libraries/AP_Compass/AP_Compass_qflight.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #pragma once #include diff --git a/libraries/AP_Compass/CompassCalibrator.cpp b/libraries/AP_Compass/CompassCalibrator.cpp index de1215eff9..75f8ad860a 100644 --- a/libraries/AP_Compass/CompassCalibrator.cpp +++ b/libraries/AP_Compass/CompassCalibrator.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Compass/Compass_learn.cpp b/libraries/AP_Compass/Compass_learn.cpp index c51d7fbc5f..43d77380a7 100644 --- a/libraries/AP_Compass/Compass_learn.cpp +++ b/libraries/AP_Compass/Compass_learn.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #include "AP_Compass.h" diff --git a/libraries/AP_Declination/AP_Declination.cpp b/libraries/AP_Declination/AP_Declination.cpp index f52a1a23d6..efbfc282fb 100644 --- a/libraries/AP_Declination/AP_Declination.cpp +++ b/libraries/AP_Declination/AP_Declination.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Declination/AP_Declination.h b/libraries/AP_Declination/AP_Declination.h index edb106ee0c..01d0e3ebc9 100644 --- a/libraries/AP_Declination/AP_Declination.h +++ b/libraries/AP_Declination/AP_Declination.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.cpp b/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.cpp index e831b4d2f5..a7a033c8b3 100644 --- a/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.cpp +++ b/libraries/AP_Declination/examples/AP_Declination_test/AP_Declination_test.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include #include diff --git a/libraries/AP_EPM/AP_EPM.cpp b/libraries/AP_EPM/AP_EPM.cpp index acd8090eba..f6ff60c8a4 100644 --- a/libraries/AP_EPM/AP_EPM.cpp +++ b/libraries/AP_EPM/AP_EPM.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* * AP_EPM.cpp * diff --git a/libraries/AP_EPM/AP_EPM.h b/libraries/AP_EPM/AP_EPM.h index e5a6eb8497..ccb50fe778 100644 --- a/libraries/AP_EPM/AP_EPM.h +++ b/libraries/AP_EPM/AP_EPM.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* * AP_EPM.h * diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp index ca35deb6ca..0215237a1a 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* Inspired by work done here https://github.com/PX4/Firmware/tree/master/src/drivers/frsky_telemetry from Stefan Rado diff --git a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h index d4fb903989..8cc57f409d 100644 --- a/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h +++ b/libraries/AP_Frsky_Telem/AP_Frsky_Telem.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index b0a0616e3a..99d4100fcb 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 27db42b16a..fd05c9dcaf 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_ERB.cpp b/libraries/AP_GPS/AP_GPS_ERB.cpp index ff9750f19d..9dbb4ab7ec 100644 --- a/libraries/AP_GPS/AP_GPS_ERB.cpp +++ b/libraries/AP_GPS/AP_GPS_ERB.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_ERB.h b/libraries/AP_GPS/AP_GPS_ERB.h index 0209ceea9a..f3b6a9a517 100644 --- a/libraries/AP_GPS/AP_GPS_ERB.h +++ b/libraries/AP_GPS/AP_GPS_ERB.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_GSOF.cpp b/libraries/AP_GPS/AP_GPS_GSOF.cpp index d622256561..acf9487b5e 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.cpp +++ b/libraries/AP_GPS/AP_GPS_GSOF.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_GSOF.h b/libraries/AP_GPS/AP_GPS_GSOF.h index dc8dc0dab2..42416f3d9b 100644 --- a/libraries/AP_GPS/AP_GPS_GSOF.h +++ b/libraries/AP_GPS/AP_GPS_GSOF.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_MAV.cpp b/libraries/AP_GPS/AP_GPS_MAV.cpp index 12d107775e..80cf1b850b 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.cpp +++ b/libraries/AP_GPS/AP_GPS_MAV.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_MAV.h b/libraries/AP_GPS/AP_GPS_MAV.h index 66f2f0d60a..b2e01ba404 100644 --- a/libraries/AP_GPS/AP_GPS_MAV.h +++ b/libraries/AP_GPS/AP_GPS_MAV.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_MTK.cpp b/libraries/AP_GPS/AP_GPS_MTK.cpp index 385d840388..18db437027 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_MTK.h b/libraries/AP_GPS/AP_GPS_MTK.h index 0b203b79bc..1c8e64017d 100644 --- a/libraries/AP_GPS/AP_GPS_MTK.h +++ b/libraries/AP_GPS/AP_GPS_MTK.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_MTK19.cpp b/libraries/AP_GPS/AP_GPS_MTK19.cpp index 4780ba9460..5312954c00 100644 --- a/libraries/AP_GPS/AP_GPS_MTK19.cpp +++ b/libraries/AP_GPS/AP_GPS_MTK19.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_MTK19.h b/libraries/AP_GPS/AP_GPS_MTK19.h index 99063e92a9..ea83206171 100644 --- a/libraries/AP_GPS/AP_GPS_MTK19.h +++ b/libraries/AP_GPS/AP_GPS_MTK19.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_MTK_Common.h b/libraries/AP_GPS/AP_GPS_MTK_Common.h index 6b8718f044..0b4cd34916 100644 --- a/libraries/AP_GPS/AP_GPS_MTK_Common.h +++ b/libraries/AP_GPS/AP_GPS_MTK_Common.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index 2b02d2f808..0ec1a1159d 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_NMEA.h b/libraries/AP_GPS/AP_GPS_NMEA.h index 5ddcdcd650..e64e461002 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.h +++ b/libraries/AP_GPS/AP_GPS_NMEA.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_NOVA.cpp b/libraries/AP_GPS/AP_GPS_NOVA.cpp index d948c04f59..7bb611dcec 100644 --- a/libraries/AP_GPS/AP_GPS_NOVA.cpp +++ b/libraries/AP_GPS/AP_GPS_NOVA.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_NOVA.h b/libraries/AP_GPS/AP_GPS_NOVA.h index 61727032fa..f6f10d56f9 100644 --- a/libraries/AP_GPS/AP_GPS_NOVA.h +++ b/libraries/AP_GPS/AP_GPS_NOVA.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_PX4.cpp b/libraries/AP_GPS/AP_GPS_PX4.cpp index 5534067d38..0b5b6a38ed 100644 --- a/libraries/AP_GPS/AP_GPS_PX4.cpp +++ b/libraries/AP_GPS/AP_GPS_PX4.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_PX4.h b/libraries/AP_GPS/AP_GPS_PX4.h index ba9d7e0075..a5d545c186 100644 --- a/libraries/AP_GPS/AP_GPS_PX4.h +++ b/libraries/AP_GPS/AP_GPS_PX4.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_QURT.cpp b/libraries/AP_GPS/AP_GPS_QURT.cpp index 980737b41c..662043de32 100644 --- a/libraries/AP_GPS/AP_GPS_QURT.cpp +++ b/libraries/AP_GPS/AP_GPS_QURT.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_QURT.h b/libraries/AP_GPS/AP_GPS_QURT.h index 788c2800b7..e67ce350c2 100644 --- a/libraries/AP_GPS/AP_GPS_QURT.h +++ b/libraries/AP_GPS/AP_GPS_QURT.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_SBF.cpp b/libraries/AP_GPS/AP_GPS_SBF.cpp index 58bdeab34b..a3ae275e72 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.cpp +++ b/libraries/AP_GPS/AP_GPS_SBF.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_SBF.h b/libraries/AP_GPS/AP_GPS_SBF.h index ce185effe8..fcae1660e5 100644 --- a/libraries/AP_GPS/AP_GPS_SBF.h +++ b/libraries/AP_GPS/AP_GPS_SBF.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_SBP.cpp b/libraries/AP_GPS/AP_GPS_SBP.cpp index e4707860ed..702d6be148 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.cpp +++ b/libraries/AP_GPS/AP_GPS_SBP.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_SBP.h b/libraries/AP_GPS/AP_GPS_SBP.h index 00b5b20bf4..f74bace873 100644 --- a/libraries/AP_GPS/AP_GPS_SBP.h +++ b/libraries/AP_GPS/AP_GPS_SBP.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_SIRF.cpp b/libraries/AP_GPS/AP_GPS_SIRF.cpp index cb9902a245..3abe84325e 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.cpp +++ b/libraries/AP_GPS/AP_GPS_SIRF.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_SIRF.h b/libraries/AP_GPS/AP_GPS_SIRF.h index e8df067af7..6779984000 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.h +++ b/libraries/AP_GPS/AP_GPS_SIRF.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 3dc9dbf529..8dacd5e874 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index b380a21df7..427513afd7 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/GPS_Backend.cpp b/libraries/AP_GPS/GPS_Backend.cpp index 80114cceb0..800f711963 100644 --- a/libraries/AP_GPS/GPS_Backend.cpp +++ b/libraries/AP_GPS/GPS_Backend.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/GPS_Backend.h b/libraries/AP_GPS/GPS_Backend.h index deda226b8a..9c9f4a07ca 100644 --- a/libraries/AP_GPS/GPS_Backend.h +++ b/libraries/AP_GPS/GPS_Backend.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_GPS/GPS_detect_state.h b/libraries/AP_GPS/GPS_detect_state.h index 111055b3ff..53ef21d045 100644 --- a/libraries/AP_GPS/GPS_detect_state.h +++ b/libraries/AP_GPS/GPS_detect_state.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by 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 6ea8c56d5f..40e1282f4c 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 @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // // Test for AP_GPS_AUTO // diff --git a/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp b/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp index d06fba9042..8f7444ddc4 100644 --- a/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp +++ b/libraries/AP_GPS/examples/GPS_UBLOX_passthrough/GPS_UBLOX_passthrough.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * GPS UBlox passthrough sketch * Code by DIYDrones.com diff --git a/libraries/AP_GPS/tests/test_gps.cpp b/libraries/AP_GPS/tests/test_gps.cpp index e5b33dc0e3..6a48bff26b 100644 --- a/libraries/AP_GPS/tests/test_gps.cpp +++ b/libraries/AP_GPS/tests/test_gps.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL/AP_HAL_Main.h b/libraries/AP_HAL/AP_HAL_Main.h index 1262d4f2b1..60203568d8 100644 --- a/libraries/AP_HAL/AP_HAL_Main.h +++ b/libraries/AP_HAL/AP_HAL_Main.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL/Device.h b/libraries/AP_HAL/Device.h index 67bce23c94..fca1da6240 100644 --- a/libraries/AP_HAL/Device.h +++ b/libraries/AP_HAL/Device.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015-2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL/I2CDevice.h b/libraries/AP_HAL/I2CDevice.h index bccc18ad4b..ff88e45712 100644 --- a/libraries/AP_HAL/I2CDevice.h +++ b/libraries/AP_HAL/I2CDevice.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015-2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL/SPIDevice.h b/libraries/AP_HAL/SPIDevice.h index 41f8f32c06..8ae4afebb7 100644 --- a/libraries/AP_HAL/SPIDevice.h +++ b/libraries/AP_HAL/SPIDevice.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015-2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL/UARTDriver.cpp b/libraries/AP_HAL/UARTDriver.cpp index 337445c176..0ad15746aa 100644 --- a/libraries/AP_HAL/UARTDriver.cpp +++ b/libraries/AP_HAL/UARTDriver.cpp @@ -1,4 +1,3 @@ -// -*- Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL/utility/OwnPtr.h b/libraries/AP_HAL/utility/OwnPtr.h index 5ca9c54682..85a8957744 100644 --- a/libraries/AP_HAL/utility/OwnPtr.h +++ b/libraries/AP_HAL/utility/OwnPtr.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015-2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL/utility/dsm.cpp b/libraries/AP_HAL/utility/dsm.cpp index 71c6d91035..c683287738 100644 --- a/libraries/AP_HAL/utility/dsm.cpp +++ b/libraries/AP_HAL/utility/dsm.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 8; Mode: C++; c-basic-offset: 8; indent-tabs-mode: -*- t -*- /* DSM decoder, based on src/modules/px4iofirmware/dsm.c from PX4Firmware modified for use in AP_HAL_* by Andrew Tridgell diff --git a/libraries/AP_HAL/utility/functor.h b/libraries/AP_HAL/utility/functor.h index 1463906693..5954700853 100644 --- a/libraries/AP_HAL/utility/functor.h +++ b/libraries/AP_HAL/utility/functor.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL/utility/print_vprintf.cpp b/libraries/AP_HAL/utility/print_vprintf.cpp index be72adb3ad..95455be1d7 100644 --- a/libraries/AP_HAL/utility/print_vprintf.cpp +++ b/libraries/AP_HAL/utility/print_vprintf.cpp @@ -1,4 +1,3 @@ -// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*- /* Adapted from the avr-libc vfprintf: diff --git a/libraries/AP_HAL/utility/srxl.cpp b/libraries/AP_HAL/utility/srxl.cpp index e3780ae6a0..054f46f02b 100644 --- a/libraries/AP_HAL/utility/srxl.cpp +++ b/libraries/AP_HAL/utility/srxl.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 8; Mode: C++; c-basic-offset: 8; indent-tabs-mode: -*- t -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL/utility/srxl.h b/libraries/AP_HAL/utility/srxl.h index 053cb70cef..257c7a9a3e 100644 --- a/libraries/AP_HAL/utility/srxl.h +++ b/libraries/AP_HAL/utility/srxl.h @@ -1,4 +1,3 @@ -// -*- tab-width: 8; Mode: C++; c-basic-offset: 8; indent-tabs-mode: -*- t -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL/utility/st24.cpp b/libraries/AP_HAL/utility/st24.cpp index 36d1191117..525f43f03a 100644 --- a/libraries/AP_HAL/utility/st24.cpp +++ b/libraries/AP_HAL/utility/st24.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 8; Mode: C++; c-basic-offset: 8; indent-tabs-mode: -*- t -*- /* st24 decoder, based on PX4Firmware/src/rc/lib/rc/st24.c from PX4Firmware modified for use in AP_HAL_* by Andrew Tridgell diff --git a/libraries/AP_HAL/utility/st24.h b/libraries/AP_HAL/utility/st24.h index 546d6b202d..fe849d9e55 100644 --- a/libraries/AP_HAL/utility/st24.h +++ b/libraries/AP_HAL/utility/st24.h @@ -1,4 +1,3 @@ -// -*- tab-width: 8; Mode: C++; c-basic-offset: 8; indent-tabs-mode: -*- t -*- /* st24 decoder, based on PX4Firmware/src/rc/lib/rc/st24.c from PX4Firmware modified for use in AP_HAL_* by Andrew Tridgell diff --git a/libraries/AP_HAL/utility/sumd.cpp b/libraries/AP_HAL/utility/sumd.cpp index fe1402d491..a36e7ef123 100644 --- a/libraries/AP_HAL/utility/sumd.cpp +++ b/libraries/AP_HAL/utility/sumd.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 8; Mode: C++; c-basic-offset: 8; indent-tabs-mode: -*- t -*- /* SUMD decoder, based on PX4Firmware/src/rc/lib/rc/sumd.c from PX4Firmware modified for use in AP_HAL_* by Andrew Tridgell diff --git a/libraries/AP_HAL/utility/sumd.h b/libraries/AP_HAL/utility/sumd.h index dac691adfd..22052a20ba 100644 --- a/libraries/AP_HAL/utility/sumd.h +++ b/libraries/AP_HAL/utility/sumd.h @@ -1,4 +1,3 @@ -// -*- tab-width: 8; Mode: C++; c-basic-offset: 8; indent-tabs-mode: -*- t -*- /* SUMD decoder, based on PX4Firmware/src/rc/lib/rc/sumd.c from PX4Firmware modified for use in AP_HAL_* by Andrew Tridgell diff --git a/libraries/AP_HAL/utility/tests/test_own_ptr.cpp b/libraries/AP_HAL/utility/tests/test_own_ptr.cpp index 4c05339c2e..6b22887837 100644 --- a/libraries/AP_HAL/utility/tests/test_own_ptr.cpp +++ b/libraries/AP_HAL/utility/tests/test_own_ptr.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015-2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Empty/I2CDevice.h b/libraries/AP_HAL_Empty/I2CDevice.h index 58905b2f70..ae3b12bad7 100644 --- a/libraries/AP_HAL_Empty/I2CDevice.h +++ b/libraries/AP_HAL_Empty/I2CDevice.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015-2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Empty/SPIDevice.h b/libraries/AP_HAL_Empty/SPIDevice.h index ee54108e3f..4e297caa6c 100644 --- a/libraries/AP_HAL_Empty/SPIDevice.h +++ b/libraries/AP_HAL_Empty/SPIDevice.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015-2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp b/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp index 39a976a05b..7326046400 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp +++ b/libraries/AP_HAL_Linux/AnalogIn_IIO.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include "AnalogIn_IIO.h" #include diff --git a/libraries/AP_HAL_Linux/AnalogIn_IIO.h b/libraries/AP_HAL_Linux/AnalogIn_IIO.h index 1c330c5964..9f1122bd2f 100644 --- a/libraries/AP_HAL_Linux/AnalogIn_IIO.h +++ b/libraries/AP_HAL_Linux/AnalogIn_IIO.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_HAL_Linux.h" diff --git a/libraries/AP_HAL_Linux/Heat.h b/libraries/AP_HAL_Linux/Heat.h index d765b74ffa..be18a5c811 100644 --- a/libraries/AP_HAL_Linux/Heat.h +++ b/libraries/AP_HAL_Linux/Heat.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL_Linux/Heat_Pwm.cpp b/libraries/AP_HAL_Linux/Heat_Pwm.cpp index c19abfe3db..29f96bf581 100644 --- a/libraries/AP_HAL_Linux/Heat_Pwm.cpp +++ b/libraries/AP_HAL_Linux/Heat_Pwm.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL_Linux/Heat_Pwm.h b/libraries/AP_HAL_Linux/Heat_Pwm.h index 6c8d559392..8ca1530b2a 100644 --- a/libraries/AP_HAL_Linux/Heat_Pwm.h +++ b/libraries/AP_HAL_Linux/Heat_Pwm.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL_Linux/I2CDevice.cpp b/libraries/AP_HAL_Linux/I2CDevice.cpp index 899a3c5346..d75a1c0439 100644 --- a/libraries/AP_HAL_Linux/I2CDevice.cpp +++ b/libraries/AP_HAL_Linux/I2CDevice.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015-2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/I2CDevice.h b/libraries/AP_HAL_Linux/I2CDevice.h index c5cfd0f923..c9b6e89007 100644 --- a/libraries/AP_HAL_Linux/I2CDevice.h +++ b/libraries/AP_HAL_Linux/I2CDevice.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015-2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/PWM_Sysfs.cpp b/libraries/AP_HAL_Linux/PWM_Sysfs.cpp index c17516d080..4e87be4eb4 100644 --- a/libraries/AP_HAL_Linux/PWM_Sysfs.cpp +++ b/libraries/AP_HAL_Linux/PWM_Sysfs.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/Perf.cpp b/libraries/AP_HAL_Linux/Perf.cpp index 33ab955d0e..3908bf9808 100644 --- a/libraries/AP_HAL_Linux/Perf.cpp +++ b/libraries/AP_HAL_Linux/Perf.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/Perf.h b/libraries/AP_HAL_Linux/Perf.h index c0a741e17c..28cdce0d43 100644 --- a/libraries/AP_HAL_Linux/Perf.h +++ b/libraries/AP_HAL_Linux/Perf.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/Poller.cpp b/libraries/AP_HAL_Linux/Poller.cpp index b5820fbc01..bc274a7d91 100644 --- a/libraries/AP_HAL_Linux/Poller.cpp +++ b/libraries/AP_HAL_Linux/Poller.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/Poller.h b/libraries/AP_HAL_Linux/Poller.h index 7dac9b07c0..26b1c0bce2 100644 --- a/libraries/AP_HAL_Linux/Poller.h +++ b/libraries/AP_HAL_Linux/Poller.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/PollerThread.cpp b/libraries/AP_HAL_Linux/PollerThread.cpp index b31e2c97ac..b74514f3eb 100644 --- a/libraries/AP_HAL_Linux/PollerThread.cpp +++ b/libraries/AP_HAL_Linux/PollerThread.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/PollerThread.h b/libraries/AP_HAL_Linux/PollerThread.h index e725a6bdd6..9b40e85b07 100644 --- a/libraries/AP_HAL_Linux/PollerThread.h +++ b/libraries/AP_HAL_Linux/PollerThread.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/RCInput_115200.cpp b/libraries/AP_HAL_Linux/RCInput_115200.cpp index 740d5ccf3d..5766d42421 100644 --- a/libraries/AP_HAL_Linux/RCInput_115200.cpp +++ b/libraries/AP_HAL_Linux/RCInput_115200.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL_Linux/RCInput_DSM.cpp b/libraries/AP_HAL_Linux/RCInput_DSM.cpp index c10f4e1d14..f5f9143111 100644 --- a/libraries/AP_HAL_Linux/RCInput_DSM.cpp +++ b/libraries/AP_HAL_Linux/RCInput_DSM.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL_Linux/RCInput_Multi.cpp b/libraries/AP_HAL_Linux/RCInput_Multi.cpp index e1dce3229d..dacad24ee4 100644 --- a/libraries/AP_HAL_Linux/RCInput_Multi.cpp +++ b/libraries/AP_HAL_Linux/RCInput_Multi.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL_Linux/RCInput_SBUS.cpp b/libraries/AP_HAL_Linux/RCInput_SBUS.cpp index 8351ca82a0..c7a38227d8 100644 --- a/libraries/AP_HAL_Linux/RCInput_SBUS.cpp +++ b/libraries/AP_HAL_Linux/RCInput_SBUS.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL_Linux/RCOutput_AeroIO.cpp b/libraries/AP_HAL_Linux/RCOutput_AeroIO.cpp index e36ada977b..ac0fb904da 100644 --- a/libraries/AP_HAL_Linux/RCOutput_AeroIO.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_AeroIO.cpp @@ -1,4 +1,3 @@ -/// -- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/RCOutput_AeroIO.h b/libraries/AP_HAL_Linux/RCOutput_AeroIO.h index 1592591fa9..04964df4e1 100644 --- a/libraries/AP_HAL_Linux/RCOutput_AeroIO.h +++ b/libraries/AP_HAL_Linux/RCOutput_AeroIO.h @@ -1,4 +1,3 @@ -/// -- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/RCOutput_Disco.cpp b/libraries/AP_HAL_Linux/RCOutput_Disco.cpp index 8cdfd24fb9..313ef4eb68 100644 --- a/libraries/AP_HAL_Linux/RCOutput_Disco.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_Disco.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2016 Andrew Tridgell. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/RCOutput_Sysfs.cpp b/libraries/AP_HAL_Linux/RCOutput_Sysfs.cpp index 8450509675..62cd22941b 100644 --- a/libraries/AP_HAL_Linux/RCOutput_Sysfs.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_Sysfs.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/RCOutput_qflight.cpp b/libraries/AP_HAL_Linux/RCOutput_qflight.cpp index 8b92bb84bb..5a9a608dc1 100644 --- a/libraries/AP_HAL_Linux/RCOutput_qflight.cpp +++ b/libraries/AP_HAL_Linux/RCOutput_qflight.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL_Linux/SPIDevice.cpp b/libraries/AP_HAL_Linux/SPIDevice.cpp index 296b11e1fd..2743c1ce66 100644 --- a/libraries/AP_HAL_Linux/SPIDevice.cpp +++ b/libraries/AP_HAL_Linux/SPIDevice.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/SPIDevice.h b/libraries/AP_HAL_Linux/SPIDevice.h index 6a7b8ecdec..4267ea8158 100644 --- a/libraries/AP_HAL_Linux/SPIDevice.h +++ b/libraries/AP_HAL_Linux/SPIDevice.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/Thread.cpp b/libraries/AP_HAL_Linux/Thread.cpp index c2a0d20696..ed26c4f168 100644 --- a/libraries/AP_HAL_Linux/Thread.cpp +++ b/libraries/AP_HAL_Linux/Thread.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/Thread.h b/libraries/AP_HAL_Linux/Thread.h index 919ad30b84..db8475fa07 100644 --- a/libraries/AP_HAL_Linux/Thread.h +++ b/libraries/AP_HAL_Linux/Thread.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_Linux/UARTDriver.cpp b/libraries/AP_HAL_Linux/UARTDriver.cpp index a355fbfb99..89946c6f79 100644 --- a/libraries/AP_HAL_Linux/UARTDriver.cpp +++ b/libraries/AP_HAL_Linux/UARTDriver.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: -*- nil -*- #include "UARTDriver.h" #include diff --git a/libraries/AP_HAL_Linux/UARTQFlight.cpp b/libraries/AP_HAL_Linux/UARTQFlight.cpp index c7dad17088..f2669b4613 100644 --- a/libraries/AP_HAL_Linux/UARTQFlight.cpp +++ b/libraries/AP_HAL_Linux/UARTQFlight.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL_Linux/qflight/dsp_functions.cpp b/libraries/AP_HAL_Linux/qflight/dsp_functions.cpp index c486f9b122..d5da21293e 100644 --- a/libraries/AP_HAL_Linux/qflight/dsp_functions.cpp +++ b/libraries/AP_HAL_Linux/qflight/dsp_functions.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL_Linux/sbus.cpp b/libraries/AP_HAL_Linux/sbus.cpp index e0a64b64dc..ac18a5d5db 100644 --- a/libraries/AP_HAL_Linux/sbus.cpp +++ b/libraries/AP_HAL_Linux/sbus.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 8; Mode: C++; c-basic-offset: 8; indent-tabs-mode: -*- t -*- /* SBUS decoder, based on src/modules/px4iofirmware/sbus.c from PX4Firmware modified for use in AP_HAL_* by Andrew Tridgell diff --git a/libraries/AP_HAL_PX4/AnalogIn.cpp b/libraries/AP_HAL_PX4/AnalogIn.cpp index 340f7f95fb..8f02df9ad2 100644 --- a/libraries/AP_HAL_PX4/AnalogIn.cpp +++ b/libraries/AP_HAL_PX4/AnalogIn.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 diff --git a/libraries/AP_HAL_PX4/AnalogIn.h b/libraries/AP_HAL_PX4/AnalogIn.h index c52ea0b6ec..ca23697619 100644 --- a/libraries/AP_HAL_PX4/AnalogIn.h +++ b/libraries/AP_HAL_PX4/AnalogIn.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_HAL_PX4.h" diff --git a/libraries/AP_HAL_PX4/GPIO.cpp b/libraries/AP_HAL_PX4/GPIO.cpp index cb56eddc3e..0ba2daecd0 100644 --- a/libraries/AP_HAL_PX4/GPIO.cpp +++ b/libraries/AP_HAL_PX4/GPIO.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 diff --git a/libraries/AP_HAL_PX4/GPIO.h b/libraries/AP_HAL_PX4/GPIO.h index 21461accdf..a39e8ab83f 100644 --- a/libraries/AP_HAL_PX4/GPIO.h +++ b/libraries/AP_HAL_PX4/GPIO.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_HAL_PX4.h" diff --git a/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp b/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp index c97b1309d4..223bb37b14 100644 --- a/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp +++ b/libraries/AP_HAL_PX4/HAL_PX4_Class.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 diff --git a/libraries/AP_HAL_PX4/I2CDevice.cpp b/libraries/AP_HAL_PX4/I2CDevice.cpp index af1ede6734..44e5fe9a97 100644 --- a/libraries/AP_HAL_PX4/I2CDevice.cpp +++ b/libraries/AP_HAL_PX4/I2CDevice.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * This file is free software: you can redistribute it and/or modify it * under the terms of the GNU General Public License as published by the diff --git a/libraries/AP_HAL_PX4/I2CDevice.h b/libraries/AP_HAL_PX4/I2CDevice.h index 2c4cf7d2a7..d256f6c81c 100644 --- a/libraries/AP_HAL_PX4/I2CDevice.h +++ b/libraries/AP_HAL_PX4/I2CDevice.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015-2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_PX4/NSHShellStream.cpp b/libraries/AP_HAL_PX4/NSHShellStream.cpp index 90314a8a0c..d1c38f9338 100644 --- a/libraries/AP_HAL_PX4/NSHShellStream.cpp +++ b/libraries/AP_HAL_PX4/NSHShellStream.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* implementation of NSH shell as a stream, for use in nsh over MAVLink diff --git a/libraries/AP_HAL_PX4/RCOutput.cpp b/libraries/AP_HAL_PX4/RCOutput.cpp index 583932572e..2f50292d28 100644 --- a/libraries/AP_HAL_PX4/RCOutput.cpp +++ b/libraries/AP_HAL_PX4/RCOutput.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 diff --git a/libraries/AP_HAL_PX4/Scheduler.cpp b/libraries/AP_HAL_PX4/Scheduler.cpp index c49276d80e..d001730581 100644 --- a/libraries/AP_HAL_PX4/Scheduler.cpp +++ b/libraries/AP_HAL_PX4/Scheduler.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 diff --git a/libraries/AP_HAL_PX4/UARTDriver.cpp b/libraries/AP_HAL_PX4/UARTDriver.cpp index f907fa9cca..1abcc5e011 100644 --- a/libraries/AP_HAL_PX4/UARTDriver.cpp +++ b/libraries/AP_HAL_PX4/UARTDriver.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 diff --git a/libraries/AP_HAL_PX4/examples/simple/simple.cpp b/libraries/AP_HAL_PX4/examples/simple/simple.cpp index a0e3e61319..0589b57217 100644 --- a/libraries/AP_HAL_PX4/examples/simple/simple.cpp +++ b/libraries/AP_HAL_PX4/examples/simple/simple.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* simple hello world sketch Andrew Tridgell September 2011 diff --git a/libraries/AP_HAL_PX4/px4_param.cpp b/libraries/AP_HAL_PX4/px4_param.cpp index 75b0adec93..e0a286c983 100644 --- a/libraries/AP_HAL_PX4/px4_param.cpp +++ b/libraries/AP_HAL_PX4/px4_param.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This replaces the PX4Firmware parameter system with dummy functions. The ArduPilot parameter system uses different formatting diff --git a/libraries/AP_HAL_QURT/RCOutput.cpp b/libraries/AP_HAL_QURT/RCOutput.cpp index 58d45d1fac..b1c7daa214 100644 --- a/libraries/AP_HAL_QURT/RCOutput.cpp +++ b/libraries/AP_HAL_QURT/RCOutput.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include #if CONFIG_HAL_BOARD == HAL_BOARD_QURT diff --git a/libraries/AP_HAL_QURT/Scheduler.cpp b/libraries/AP_HAL_QURT/Scheduler.cpp index c0747d2521..a25493418d 100644 --- a/libraries/AP_HAL_QURT/Scheduler.cpp +++ b/libraries/AP_HAL_QURT/Scheduler.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_QURT diff --git a/libraries/AP_HAL_SITL/AnalogIn.cpp b/libraries/AP_HAL_SITL/AnalogIn.cpp index 31bde3b56c..957c27fdba 100644 --- a/libraries/AP_HAL_SITL/AnalogIn.cpp +++ b/libraries/AP_HAL_SITL/AnalogIn.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp index a7b5968213..84eedd0ddc 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/AP_HAL_SITL/SITL_State.cpp b/libraries/AP_HAL_SITL/SITL_State.cpp index cbbcab12e6..dc7097f0da 100644 --- a/libraries/AP_HAL_SITL/SITL_State.cpp +++ b/libraries/AP_HAL_SITL/SITL_State.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index 232eda6859..6f71e1ac7a 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/AP_HAL_SITL/Scheduler.cpp b/libraries/AP_HAL_SITL/Scheduler.cpp index 3d9b4efaf9..47ab857add 100644 --- a/libraries/AP_HAL_SITL/Scheduler.cpp +++ b/libraries/AP_HAL_SITL/Scheduler.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_SITL diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 968aa9c582..5bd1383008 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -1,4 +1,3 @@ -// -*- Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_HAL_SITL/UARTDriver.h b/libraries/AP_HAL_SITL/UARTDriver.h index d50e6886a7..34fde551ef 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.h +++ b/libraries/AP_HAL_SITL/UARTDriver.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_HAL_SITL/sitl_gps.cpp b/libraries/AP_HAL_SITL/sitl_gps.cpp index 63870399be..cdafb95c75 100644 --- a/libraries/AP_HAL_SITL/sitl_gps.cpp +++ b/libraries/AP_HAL_SITL/sitl_gps.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* SITL handling diff --git a/libraries/AP_HAL_VRBRAIN/AnalogIn.cpp b/libraries/AP_HAL_VRBRAIN/AnalogIn.cpp index 8fcc7c6324..5db8475f12 100644 --- a/libraries/AP_HAL_VRBRAIN/AnalogIn.cpp +++ b/libraries/AP_HAL_VRBRAIN/AnalogIn.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN diff --git a/libraries/AP_HAL_VRBRAIN/AnalogIn.h b/libraries/AP_HAL_VRBRAIN/AnalogIn.h index ce999d946d..eb55bd7910 100644 --- a/libraries/AP_HAL_VRBRAIN/AnalogIn.h +++ b/libraries/AP_HAL_VRBRAIN/AnalogIn.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_HAL_VRBRAIN.h" diff --git a/libraries/AP_HAL_VRBRAIN/GPIO.cpp b/libraries/AP_HAL_VRBRAIN/GPIO.cpp index 76e37f5cad..6b46633226 100644 --- a/libraries/AP_HAL_VRBRAIN/GPIO.cpp +++ b/libraries/AP_HAL_VRBRAIN/GPIO.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN diff --git a/libraries/AP_HAL_VRBRAIN/GPIO.h b/libraries/AP_HAL_VRBRAIN/GPIO.h index e87a2c5d93..cc1d818638 100644 --- a/libraries/AP_HAL_VRBRAIN/GPIO.h +++ b/libraries/AP_HAL_VRBRAIN/GPIO.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_HAL_VRBRAIN.h" diff --git a/libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp b/libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp index 1e3eecb4ff..6a73271a26 100644 --- a/libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp +++ b/libraries/AP_HAL_VRBRAIN/HAL_VRBRAIN_Class.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN diff --git a/libraries/AP_HAL_VRBRAIN/I2CDevice.cpp b/libraries/AP_HAL_VRBRAIN/I2CDevice.cpp index 74df2a1f8e..36b4b15abb 100644 --- a/libraries/AP_HAL_VRBRAIN/I2CDevice.cpp +++ b/libraries/AP_HAL_VRBRAIN/I2CDevice.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * This file is free software: you can redistribute it and/or modify it * under the terms of the GNU General Public License as published by the diff --git a/libraries/AP_HAL_VRBRAIN/I2CDevice.h b/libraries/AP_HAL_VRBRAIN/I2CDevice.h index 656287053c..c132c3e64e 100644 --- a/libraries/AP_HAL_VRBRAIN/I2CDevice.h +++ b/libraries/AP_HAL_VRBRAIN/I2CDevice.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015-2016 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_HAL_VRBRAIN/NSHShellStream.cpp b/libraries/AP_HAL_VRBRAIN/NSHShellStream.cpp index 96787e10a4..cf040303ac 100644 --- a/libraries/AP_HAL_VRBRAIN/NSHShellStream.cpp +++ b/libraries/AP_HAL_VRBRAIN/NSHShellStream.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* implementation of NSH shell as a stream, for use in nsh over MAVLink diff --git a/libraries/AP_HAL_VRBRAIN/RCOutput.cpp b/libraries/AP_HAL_VRBRAIN/RCOutput.cpp index 08c1985225..0ca0eef3c9 100644 --- a/libraries/AP_HAL_VRBRAIN/RCOutput.cpp +++ b/libraries/AP_HAL_VRBRAIN/RCOutput.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN diff --git a/libraries/AP_HAL_VRBRAIN/Scheduler.cpp b/libraries/AP_HAL_VRBRAIN/Scheduler.cpp index e047e9fbc0..3d01f2df87 100644 --- a/libraries/AP_HAL_VRBRAIN/Scheduler.cpp +++ b/libraries/AP_HAL_VRBRAIN/Scheduler.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN diff --git a/libraries/AP_HAL_VRBRAIN/UARTDriver.cpp b/libraries/AP_HAL_VRBRAIN/UARTDriver.cpp index 286001a620..d331428d7f 100644 --- a/libraries/AP_HAL_VRBRAIN/UARTDriver.cpp +++ b/libraries/AP_HAL_VRBRAIN/UARTDriver.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN diff --git a/libraries/AP_HAL_VRBRAIN/vrbrain_param.cpp b/libraries/AP_HAL_VRBRAIN/vrbrain_param.cpp index 82aefb3f64..12fdfba0ba 100644 --- a/libraries/AP_HAL_VRBRAIN/vrbrain_param.cpp +++ b/libraries/AP_HAL_VRBRAIN/vrbrain_param.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This replaces the PX4Firmware parameter system with dummy functions. The ArduPilot parameter system uses different formatting diff --git a/libraries/AP_ICEngine/AP_ICEngine.cpp b/libraries/AP_ICEngine/AP_ICEngine.cpp index a5fa878b33..4c902a8fc7 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.cpp +++ b/libraries/AP_ICEngine/AP_ICEngine.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_ICEngine/AP_ICEngine.h b/libraries/AP_ICEngine/AP_ICEngine.h index 4004223f9f..709580c3e6 100644 --- a/libraries/AP_ICEngine/AP_ICEngine.h +++ b/libraries/AP_ICEngine/AP_ICEngine.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_InertialNav/AP_InertialNav.h b/libraries/AP_InertialNav/AP_InertialNav.h index d5da655bba..afcdc62a4f 100644 --- a/libraries/AP_InertialNav/AP_InertialNav.h +++ b/libraries/AP_InertialNav/AP_InertialNav.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp index 5f6ad615bb..998a930ee9 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include "AP_InertialNav.h" diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h index 9e338d2c3b..ecdb4d452f 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* A wrapper around the AP_InertialNav class which uses the NavEKF filter if available, and falls back to the AP_InertialNav filter diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index 134bdf8554..d098f58764 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index c792362217..9ce3b3c595 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once // Gyro and Accelerometer calibration criteria diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp index ffbe3c8577..60d06a09eb 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include "AP_InertialSensor.h" #include "AP_InertialSensor_Backend.h" diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h index 89bba8055c..53d3ac06ea 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_Backend.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp index a485f927ce..d246051e51 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_HIL.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include "AP_InertialSensor_HIL.h" diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_HIL.h b/libraries/AP_InertialSensor/AP_InertialSensor_HIL.h index f3f326d23d..aad861f6ac 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_HIL.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_HIL.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_InertialSensor.h" diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp index 91904c8df2..798d61f42c 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h b/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h index 1ce4ce96f8..fe04bdcf7b 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_L3G4200D.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp index a597ec0332..3cac5f9d14 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h index 534f7a2d0d..fbc054e02c 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU6000.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp index 16a3b7f3d8..3e343966d2 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.h b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.h index 0c6a008443..61ddaa8ab0 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_MPU9250.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp index fa4cbed33b..515b7b8786 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_PX4.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 || CONFIG_HAL_BOARD == HAL_BOARD_VRBRAIN diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_PX4.h b/libraries/AP_InertialSensor/AP_InertialSensor_PX4.h index 150a5fe1f6..1a9e0a7264 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_PX4.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_PX4.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_QURT.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_QURT.cpp index 92abce6ac4..8757f2023f 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_QURT.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_QURT.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include "AP_InertialSensor_QURT.h" diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_QURT.h b/libraries/AP_InertialSensor/AP_InertialSensor_QURT.h index bec9b2896f..bc60ad5f0b 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_QURT.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_QURT.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp index 8b61ddf051..6a9ce7b24a 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include "AP_InertialSensor_SITL.h" #include diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.h b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.h index 75fefc61f9..6539a31a79 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_SITL.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_SITL.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp index d69f0b4865..80d0fa3d16 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_UserInteract_MAVLink.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include #include diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_qflight.cpp b/libraries/AP_InertialSensor/AP_InertialSensor_qflight.cpp index 0900653d8f..200a8f9f7b 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_qflight.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor_qflight.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_QFLIGHT diff --git a/libraries/AP_InertialSensor/AP_InertialSensor_qflight.h b/libraries/AP_InertialSensor/AP_InertialSensor_qflight.h index 317c51bb23..ee55ce0180 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor_qflight.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor_qflight.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_InertialSensor/AuxiliaryBus.h b/libraries/AP_InertialSensor/AuxiliaryBus.h index d67779e657..38f2d64f6d 100644 --- a/libraries/AP_InertialSensor/AuxiliaryBus.h +++ b/libraries/AP_InertialSensor/AuxiliaryBus.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp b/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp index dad6e40b7f..90de0a4d00 100644 --- a/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp +++ b/libraries/AP_InertialSensor/examples/INS_generic/INS_generic.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // // Simple test for the AP_InertialSensor driver. // diff --git a/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp b/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp index f450a15353..a65f467977 100644 --- a/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp +++ b/libraries/AP_InertialSensor/examples/VibTest/VibTest.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // // test harness for vibration testing // diff --git a/libraries/AP_L1_Control/AP_L1_Control.cpp b/libraries/AP_L1_Control/AP_L1_Control.cpp index 9198a681a7..fd91c685a4 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.cpp +++ b/libraries/AP_L1_Control/AP_L1_Control.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include "AP_L1_Control.h" diff --git a/libraries/AP_L1_Control/AP_L1_Control.h b/libraries/AP_L1_Control/AP_L1_Control.h index 23d05191bf..ab8ce2f593 100644 --- a/libraries/AP_L1_Control/AP_L1_Control.h +++ b/libraries/AP_L1_Control/AP_L1_Control.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once /// @file AP_L1_Control.h diff --git a/libraries/AP_LandingGear/AP_LandingGear.cpp b/libraries/AP_LandingGear/AP_LandingGear.cpp index 89a453279f..9dec25d382 100644 --- a/libraries/AP_LandingGear/AP_LandingGear.cpp +++ b/libraries/AP_LandingGear/AP_LandingGear.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "AP_LandingGear.h" #include #include diff --git a/libraries/AP_LandingGear/AP_LandingGear.h b/libraries/AP_LandingGear/AP_LandingGear.h index 091189ea04..31adef6a03 100644 --- a/libraries/AP_LandingGear/AP_LandingGear.h +++ b/libraries/AP_LandingGear/AP_LandingGear.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_LandingGear.h /// @brief Landing gear control library #pragma once diff --git a/libraries/AP_Math/edc.h b/libraries/AP_Math/edc.h index 7411cb9dc7..f40792889e 100644 --- a/libraries/AP_Math/edc.h +++ b/libraries/AP_Math/edc.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Math/examples/eulers/eulers.cpp b/libraries/AP_Math/examples/eulers/eulers.cpp index e436b78693..6f8a4f153b 100644 --- a/libraries/AP_Math/examples/eulers/eulers.cpp +++ b/libraries/AP_Math/examples/eulers/eulers.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // // Unit tests for the AP_Math euler code // diff --git a/libraries/AP_Math/examples/location/location.cpp b/libraries/AP_Math/examples/location/location.cpp index 30e2424da8..1697f0496a 100644 --- a/libraries/AP_Math/examples/location/location.cpp +++ b/libraries/AP_Math/examples/location/location.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // // Unit tests for the AP_Math polygon code // diff --git a/libraries/AP_Math/examples/matrix_alg/matrix_alg.cpp b/libraries/AP_Math/examples/matrix_alg/matrix_alg.cpp index 386ba481f1..38d698e5bd 100644 --- a/libraries/AP_Math/examples/matrix_alg/matrix_alg.cpp +++ b/libraries/AP_Math/examples/matrix_alg/matrix_alg.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // // Unit tests for the AP_Math rotations code // diff --git a/libraries/AP_Math/examples/polygon/polygon.cpp b/libraries/AP_Math/examples/polygon/polygon.cpp index 6a52584887..a33803a863 100644 --- a/libraries/AP_Math/examples/polygon/polygon.cpp +++ b/libraries/AP_Math/examples/polygon/polygon.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // // Unit tests for the AP_Math polygon code // diff --git a/libraries/AP_Math/examples/rotations/rotations.cpp b/libraries/AP_Math/examples/rotations/rotations.cpp index 8a01220493..df4bd33c27 100644 --- a/libraries/AP_Math/examples/rotations/rotations.cpp +++ b/libraries/AP_Math/examples/rotations/rotations.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- // // Unit tests for the AP_Math rotations code // diff --git a/libraries/AP_Math/location.cpp b/libraries/AP_Math/location.cpp index 0d589ec8fd..d980674e7f 100644 --- a/libraries/AP_Math/location.cpp +++ b/libraries/AP_Math/location.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * location.cpp * Copyright (C) Andrew Tridgell 2011 diff --git a/libraries/AP_Math/matrix3.cpp b/libraries/AP_Math/matrix3.cpp index a6ce6e64f6..e930365cbc 100644 --- a/libraries/AP_Math/matrix3.cpp +++ b/libraries/AP_Math/matrix3.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * matrix3.cpp * Copyright (C) Andrew Tridgell 2012 diff --git a/libraries/AP_Math/matrix3.h b/libraries/AP_Math/matrix3.h index 2009f7da85..024b883dd3 100644 --- a/libraries/AP_Math/matrix3.h +++ b/libraries/AP_Math/matrix3.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Math/matrix_alg.cpp b/libraries/AP_Math/matrix_alg.cpp index bce9b43d0b..1fd863fa3c 100644 --- a/libraries/AP_Math/matrix_alg.cpp +++ b/libraries/AP_Math/matrix_alg.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * matrix3.cpp * Copyright (C) Siddharth Bharat Purohit, 3DRobotics Inc. 2015 diff --git a/libraries/AP_Math/polygon.cpp b/libraries/AP_Math/polygon.cpp index c34b9abbbf..8a19de8193 100644 --- a/libraries/AP_Math/polygon.cpp +++ b/libraries/AP_Math/polygon.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * polygon.cpp * Copyright (C) Andrew Tridgell 2011 diff --git a/libraries/AP_Math/polygon.h b/libraries/AP_Math/polygon.h index ab70c43b57..0955fb61ad 100644 --- a/libraries/AP_Math/polygon.h +++ b/libraries/AP_Math/polygon.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * polygon.h * Copyright (C) Andrew Tridgell 2011 diff --git a/libraries/AP_Math/quaternion.cpp b/libraries/AP_Math/quaternion.cpp index a5047b3671..d4b2789a9f 100644 --- a/libraries/AP_Math/quaternion.cpp +++ b/libraries/AP_Math/quaternion.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * quaternion.cpp * Copyright (C) Andrew Tridgell 2012 diff --git a/libraries/AP_Math/quaternion.h b/libraries/AP_Math/quaternion.h index 5e0dd92828..ddf35ebbbc 100644 --- a/libraries/AP_Math/quaternion.h +++ b/libraries/AP_Math/quaternion.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Math/rotations.h b/libraries/AP_Math/rotations.h index 68bb9d4853..0d0f333b74 100644 --- a/libraries/AP_Math/rotations.h +++ b/libraries/AP_Math/rotations.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * rotations.h * Copyright (C) Andrew Tridgell 2012 diff --git a/libraries/AP_Math/vector2.cpp b/libraries/AP_Math/vector2.cpp index c2679b232b..e613b2af07 100644 --- a/libraries/AP_Math/vector2.cpp +++ b/libraries/AP_Math/vector2.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * vector3.cpp * Copyright (C) Andrew Tridgell 2012 diff --git a/libraries/AP_Math/vector2.h b/libraries/AP_Math/vector2.h index d535df35e9..d2284d6b68 100644 --- a/libraries/AP_Math/vector2.h +++ b/libraries/AP_Math/vector2.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Math/vector3.cpp b/libraries/AP_Math/vector3.cpp index b67cbf59ad..771d39c6e4 100644 --- a/libraries/AP_Math/vector3.cpp +++ b/libraries/AP_Math/vector3.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * vector3.cpp * Copyright (C) Andrew Tridgell 2012 diff --git a/libraries/AP_Math/vector3.h b/libraries/AP_Math/vector3.h index 16c3022554..e5b5b55b42 100644 --- a/libraries/AP_Math/vector3.h +++ b/libraries/AP_Math/vector3.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Math/vectorN.h b/libraries/AP_Math/vectorN.h index 9328541408..eab36a2f5e 100644 --- a/libraries/AP_Math/vectorN.h +++ b/libraries/AP_Math/vectorN.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Menu/AP_Menu.cpp b/libraries/AP_Menu/AP_Menu.cpp index 55558b4305..2d8eced540 100644 --- a/libraries/AP_Menu/AP_Menu.cpp +++ b/libraries/AP_Menu/AP_Menu.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // // Simple commandline menu system. #include "AP_Menu.h" diff --git a/libraries/AP_Menu/AP_Menu.h b/libraries/AP_Menu/AP_Menu.h index 55b0d794df..7e5188f1dc 100644 --- a/libraries/AP_Menu/AP_Menu.h +++ b/libraries/AP_Menu/AP_Menu.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file menu.h /// @brief Simple commandline menu subsystem. /// @discussion diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 8ac5cbd09c..cd3acea6d7 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_Mission.cpp /// @brief Handles the MAVLINK command mission stack. Reads and writes mission to storage. diff --git a/libraries/AP_Mission/AP_Mission.h b/libraries/AP_Mission/AP_Mission.h index 6ae4aed9ce..30f3ec8da9 100644 --- a/libraries/AP_Mission/AP_Mission.h +++ b/libraries/AP_Mission/AP_Mission.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_Mission.h /// @brief Handles the MAVLINK command mission stack. Reads and writes mission to storage. diff --git a/libraries/AP_Module/AP_Module.cpp b/libraries/AP_Module/AP_Module.cpp index e9609a6d3d..dffcd090c3 100644 --- a/libraries/AP_Module/AP_Module.cpp +++ b/libraries/AP_Module/AP_Module.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Module/AP_Module.h b/libraries/AP_Module/AP_Module.h index 429abd6b52..d3b5b14ed4 100644 --- a/libraries/AP_Module/AP_Module.h +++ b/libraries/AP_Module/AP_Module.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Module/AP_Module_Structures.h b/libraries/AP_Module/AP_Module_Structures.h index 692e53d0b9..9fa175d9c5 100644 --- a/libraries/AP_Module/AP_Module_Structures.h +++ b/libraries/AP_Module/AP_Module_Structures.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* this defines data structures for public module interfaces in ArduPilot. diff --git a/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp b/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp index 52cce249dc..dea026e4c3 100644 --- a/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp +++ b/libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // // Simple test for the AP_AHRS interface // diff --git a/libraries/AP_Motors/AP_Motors.h b/libraries/AP_Motors/AP_Motors.h index 2a66949b97..2911f739ff 100644 --- a/libraries/AP_Motors/AP_Motors.h +++ b/libraries/AP_Motors/AP_Motors.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_Motors_Class.h" diff --git a/libraries/AP_Motors/AP_MotorsCoax.cpp b/libraries/AP_Motors/AP_MotorsCoax.cpp index 7439590c5b..495c685a19 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.cpp +++ b/libraries/AP_Motors/AP_MotorsCoax.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_MotorsCoax.h b/libraries/AP_Motors/AP_MotorsCoax.h index 392b7f5e81..55cb187999 100644 --- a/libraries/AP_Motors/AP_MotorsCoax.h +++ b/libraries/AP_Motors/AP_MotorsCoax.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_MotorsCoax.h /// @brief Motor and Servo control class for Co-axial helicopters with two motors and two flaps #pragma once diff --git a/libraries/AP_Motors/AP_MotorsHeli.cpp b/libraries/AP_Motors/AP_MotorsHeli.cpp index 613755f802..c519c65b80 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_MotorsHeli.h b/libraries/AP_Motors/AP_MotorsHeli.h index fe2408dbe2..8c3d8a99d1 100644 --- a/libraries/AP_Motors/AP_MotorsHeli.h +++ b/libraries/AP_Motors/AP_MotorsHeli.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_MotorsHeli.h /// @brief Motor control class for Traditional Heli #pragma once diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp b/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp index b68e1fe358..3f9a0546ed 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_MotorsHeli_RSC.h b/libraries/AP_Motors/AP_MotorsHeli_RSC.h index 75cf4d80d2..5b0d02b018 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_RSC.h +++ b/libraries/AP_Motors/AP_MotorsHeli_RSC.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp index a69c291a9f..5f7f57b6a7 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.cpp +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * This program is free software: you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_MotorsHeli_Single.h b/libraries/AP_Motors/AP_MotorsHeli_Single.h index 7a38a47048..f8a8b99d55 100644 --- a/libraries/AP_Motors/AP_MotorsHeli_Single.h +++ b/libraries/AP_Motors/AP_MotorsHeli_Single.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_MotorsHeli_Single.h /// @brief Motor control class for traditional heli #pragma once diff --git a/libraries/AP_Motors/AP_MotorsHexa.cpp b/libraries/AP_Motors/AP_MotorsHexa.cpp index 0e55c13d28..5311d8f67a 100644 --- a/libraries/AP_Motors/AP_MotorsHexa.cpp +++ b/libraries/AP_Motors/AP_MotorsHexa.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_MotorsHexa.h b/libraries/AP_Motors/AP_MotorsHexa.h index 134ad64c12..4993da25d7 100644 --- a/libraries/AP_Motors/AP_MotorsHexa.h +++ b/libraries/AP_Motors/AP_MotorsHexa.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_MotorsHexa.h /// @brief Motor control class for Hexacopters #pragma once diff --git a/libraries/AP_Motors/AP_MotorsMatrix.cpp b/libraries/AP_Motors/AP_MotorsMatrix.cpp index c9d477e68b..816256dd02 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.cpp +++ b/libraries/AP_Motors/AP_MotorsMatrix.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_MotorsMatrix.h b/libraries/AP_Motors/AP_MotorsMatrix.h index 24d50f1170..dfed758478 100644 --- a/libraries/AP_Motors/AP_MotorsMatrix.h +++ b/libraries/AP_Motors/AP_MotorsMatrix.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_MotorsMatrix.h /// @brief Motor control class for Matrixcopters #pragma once diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.cpp b/libraries/AP_Motors/AP_MotorsMulticopter.cpp index 725ecbe69d..3369c47619 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.cpp +++ b/libraries/AP_Motors/AP_MotorsMulticopter.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_MotorsMulticopter.h b/libraries/AP_Motors/AP_MotorsMulticopter.h index 7c1336eb6c..1a3c2e8d76 100644 --- a/libraries/AP_Motors/AP_MotorsMulticopter.h +++ b/libraries/AP_Motors/AP_MotorsMulticopter.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_MotorsMulticopter.h /// @brief Motor control class for Multicopters #pragma once diff --git a/libraries/AP_Motors/AP_MotorsOcta.cpp b/libraries/AP_Motors/AP_MotorsOcta.cpp index 46b3bb621d..fe9df59f83 100644 --- a/libraries/AP_Motors/AP_MotorsOcta.cpp +++ b/libraries/AP_Motors/AP_MotorsOcta.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_MotorsOcta.h b/libraries/AP_Motors/AP_MotorsOcta.h index 858c0cf290..0b3ffeb65f 100644 --- a/libraries/AP_Motors/AP_MotorsOcta.h +++ b/libraries/AP_Motors/AP_MotorsOcta.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_MotorsOcta.h /// @brief Motor control class for Octacopters #pragma once diff --git a/libraries/AP_Motors/AP_MotorsOctaQuad.cpp b/libraries/AP_Motors/AP_MotorsOctaQuad.cpp index 7de2efa7a7..fff9fc1286 100644 --- a/libraries/AP_Motors/AP_MotorsOctaQuad.cpp +++ b/libraries/AP_Motors/AP_MotorsOctaQuad.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_MotorsOctaQuad.h b/libraries/AP_Motors/AP_MotorsOctaQuad.h index 4c8e5f7556..ae655ffc32 100644 --- a/libraries/AP_Motors/AP_MotorsOctaQuad.h +++ b/libraries/AP_Motors/AP_MotorsOctaQuad.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_MotorsOctaQuad.h /// @brief Motor control class for OctaQuadcopters #pragma once diff --git a/libraries/AP_Motors/AP_MotorsQuad.cpp b/libraries/AP_Motors/AP_MotorsQuad.cpp index 7efcc39080..928ff293ab 100644 --- a/libraries/AP_Motors/AP_MotorsQuad.cpp +++ b/libraries/AP_Motors/AP_MotorsQuad.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_MotorsQuad.h b/libraries/AP_Motors/AP_MotorsQuad.h index 3dfb0c7079..78514d493e 100644 --- a/libraries/AP_Motors/AP_MotorsQuad.h +++ b/libraries/AP_Motors/AP_MotorsQuad.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_MotorsQuad.h /// @brief Motor control class for Quadcopters #pragma once diff --git a/libraries/AP_Motors/AP_MotorsSingle.cpp b/libraries/AP_Motors/AP_MotorsSingle.cpp index 9f9c3965ac..7daf7efbd1 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.cpp +++ b/libraries/AP_Motors/AP_MotorsSingle.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_MotorsSingle.h b/libraries/AP_Motors/AP_MotorsSingle.h index 0440f81cda..d6f511e480 100644 --- a/libraries/AP_Motors/AP_MotorsSingle.h +++ b/libraries/AP_Motors/AP_MotorsSingle.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_MotorsSingle.h /// @brief Motor and Servo control class for Singlecopters #pragma once diff --git a/libraries/AP_Motors/AP_MotorsTri.cpp b/libraries/AP_Motors/AP_MotorsTri.cpp index c26633303d..a70a79d57a 100644 --- a/libraries/AP_Motors/AP_MotorsTri.cpp +++ b/libraries/AP_Motors/AP_MotorsTri.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_MotorsTri.h b/libraries/AP_Motors/AP_MotorsTri.h index 2ae0ac41e8..58f1f2c578 100644 --- a/libraries/AP_Motors/AP_MotorsTri.h +++ b/libraries/AP_Motors/AP_MotorsTri.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_MotorsTri.h /// @brief Motor control class for Tricopters #pragma once diff --git a/libraries/AP_Motors/AP_MotorsY6.cpp b/libraries/AP_Motors/AP_MotorsY6.cpp index fc99e153dc..fc36707d47 100644 --- a/libraries/AP_Motors/AP_MotorsY6.cpp +++ b/libraries/AP_Motors/AP_MotorsY6.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_MotorsY6.h b/libraries/AP_Motors/AP_MotorsY6.h index 5b2b21a81e..1f2ff50cef 100644 --- a/libraries/AP_Motors/AP_MotorsY6.h +++ b/libraries/AP_Motors/AP_MotorsY6.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_MotorsY6.h /// @brief Motor control class for Y6 frames #pragma once diff --git a/libraries/AP_Motors/AP_Motors_Class.cpp b/libraries/AP_Motors/AP_Motors_Class.cpp index 7d9354220e..27c1ec0ac9 100644 --- a/libraries/AP_Motors/AP_Motors_Class.cpp +++ b/libraries/AP_Motors/AP_Motors_Class.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Motors/AP_Motors_Class.h b/libraries/AP_Motors/AP_Motors_Class.h index 251ef0a0d5..ce5355c2aa 100644 --- a/libraries/AP_Motors/AP_Motors_Class.h +++ b/libraries/AP_Motors/AP_Motors_Class.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_Mount/AP_Mount.cpp b/libraries/AP_Mount/AP_Mount.cpp index 9becf150ba..33dc2377b5 100644 --- a/libraries/AP_Mount/AP_Mount.cpp +++ b/libraries/AP_Mount/AP_Mount.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include #include "AP_Mount.h" diff --git a/libraries/AP_Mount/AP_Mount.h b/libraries/AP_Mount/AP_Mount.h index 34a924376d..0a24bb403a 100644 --- a/libraries/AP_Mount/AP_Mount.h +++ b/libraries/AP_Mount/AP_Mount.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /************************************************************ * AP_mount -- library to control a 2 or 3 axis mount. * * * diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.cpp b/libraries/AP_Mount/AP_Mount_Alexmos.cpp index c679430d30..970b524b7e 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.cpp +++ b/libraries/AP_Mount/AP_Mount_Alexmos.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #include "AP_Mount_Alexmos.h" extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_Mount/AP_Mount_Alexmos.h b/libraries/AP_Mount/AP_Mount_Alexmos.h index 6a8b42b476..3d5a0b0333 100644 --- a/libraries/AP_Mount/AP_Mount_Alexmos.h +++ b/libraries/AP_Mount/AP_Mount_Alexmos.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* Alexmos Serial controlled mount backend class */ diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index 393ff62a61..c689ac85ab 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "AP_Mount_Backend.h" extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index 08e6351924..8ee5ac70d2 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.cpp b/libraries/AP_Mount/AP_Mount_SToRM32.cpp index b49cd9b681..5db807400d 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "AP_Mount_SToRM32.h" #include #include diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.h b/libraries/AP_Mount/AP_Mount_SToRM32.h index 1da77aa983..be7545e49e 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* SToRM32 mount backend class */ diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp index b44447588e..8e4d0ca618 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "AP_Mount_SToRM32_serial.h" #include #include diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h index 1f9ff51b84..57bd52c160 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.h +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* SToRM32 mount using serial protocol backend class */ diff --git a/libraries/AP_Mount/AP_Mount_Servo.cpp b/libraries/AP_Mount/AP_Mount_Servo.cpp index 9b6398842d..8aa80bfc8d 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.cpp +++ b/libraries/AP_Mount/AP_Mount_Servo.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "AP_Mount_Servo.h" extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_Mount/AP_Mount_Servo.h b/libraries/AP_Mount/AP_Mount_Servo.h index 5f0a1310e9..ffd8818d13 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.h +++ b/libraries/AP_Mount/AP_Mount_Servo.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* Servo controlled mount backend class */ diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp index 5855188dc0..21e962d2fa 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include #if AP_AHRS_NAVEKF_AVAILABLE diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.h b/libraries/AP_Mount/AP_Mount_SoloGimbal.h index 4d985396a2..3e4f08d085 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.h +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* MAVLink enabled mount backend class */ diff --git a/libraries/AP_Mount/SoloGimbal.cpp b/libraries/AP_Mount/SoloGimbal.cpp index 56ab510d4c..1890f2c3e4 100644 --- a/libraries/AP_Mount/SoloGimbal.cpp +++ b/libraries/AP_Mount/SoloGimbal.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include #if AP_AHRS_NAVEKF_AVAILABLE diff --git a/libraries/AP_Mount/SoloGimbal.h b/libraries/AP_Mount/SoloGimbal.h index 734d05511c..36d10aec8b 100644 --- a/libraries/AP_Mount/SoloGimbal.h +++ b/libraries/AP_Mount/SoloGimbal.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /************************************************************ * SoloGimbal -- library to control a 3 axis rate gimbal. * * * diff --git a/libraries/AP_Mount/SoloGimbalEKF.cpp b/libraries/AP_Mount/SoloGimbalEKF.cpp index c982a5c9c8..fd88d2ae2c 100644 --- a/libraries/AP_Mount/SoloGimbalEKF.cpp +++ b/libraries/AP_Mount/SoloGimbalEKF.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 diff --git a/libraries/AP_Mount/SoloGimbalEKF.h b/libraries/AP_Mount/SoloGimbalEKF.h index a700976dd2..3a2fbbb0db 100644 --- a/libraries/AP_Mount/SoloGimbalEKF.h +++ b/libraries/AP_Mount/SoloGimbalEKF.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* smaller EKF for simpler estimation applications diff --git a/libraries/AP_NavEKF/AP_NavEKF.cpp b/libraries/AP_NavEKF/AP_NavEKF.cpp index 35bfd40d49..a6e886f13d 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include "AP_NavEKF.h" diff --git a/libraries/AP_NavEKF/AP_NavEKF.h b/libraries/AP_NavEKF/AP_NavEKF.h index 6c34f22f8c..0a9cd1b5f3 100644 --- a/libraries/AP_NavEKF/AP_NavEKF.h +++ b/libraries/AP_NavEKF/AP_NavEKF.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* 22 state EKF based on https://github.com/priseborough/InertialNav diff --git a/libraries/AP_NavEKF/AP_NavEKF_core.cpp b/libraries/AP_NavEKF/AP_NavEKF_core.cpp index 63b32990d9..98f4645ee0 100644 --- a/libraries/AP_NavEKF/AP_NavEKF_core.cpp +++ b/libraries/AP_NavEKF/AP_NavEKF_core.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include "AP_NavEKF_core.h" diff --git a/libraries/AP_NavEKF/AP_NavEKF_core.h b/libraries/AP_NavEKF/AP_NavEKF_core.h index c3b8426419..dafc13d915 100644 --- a/libraries/AP_NavEKF/AP_NavEKF_core.h +++ b/libraries/AP_NavEKF/AP_NavEKF_core.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* 22 state EKF based on https://github.com/priseborough/InertialNav diff --git a/libraries/AP_NavEKF/AP_Nav_Common.h b/libraries/AP_NavEKF/AP_Nav_Common.h index b538f87e27..7da45aa9e9 100644 --- a/libraries/AP_NavEKF/AP_Nav_Common.h +++ b/libraries/AP_NavEKF/AP_Nav_Common.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* AP_Nav_Common holds definitions shared by inertial and ekf nav filters diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index caca0430d1..a370deb52c 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.h b/libraries/AP_NavEKF2/AP_NavEKF2.h index 491a1637c8..91f9d391ce 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* 24 state EKF based on https://github.com/priseborough/InertialNav Converted from Matlab to C++ by Paul Riseborough diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp index c03ca2a1f3..20cd9d97cd 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_AirDataFusion.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Buffer.h b/libraries/AP_NavEKF2/AP_NavEKF2_Buffer.h index 5cae2d1e9f..7de44cdac3 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Buffer.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Buffer.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // EKF Buffer models // this buffer model is to be used for observation buffers, diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp index d3b154ff20..792dfc6d59 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Control.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp index 76912d4c73..5542f7b548 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_MagFusion.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp index 79e54a54ab..06b5f6e425 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_OptFlowFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_OptFlowFusion.cpp index a46a930bc1..eb377d34d0 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_OptFlowFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_OptFlowFusion.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp index 8b2e48abf4..57677191bc 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_Outputs.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp index 2bebac1075..51bf735b19 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_PosVelFusion.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp index 26ea211dfe..a1945ad589 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_VehicleStatus.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp index 65a142c75f..a85c4b35f0 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 diff --git a/libraries/AP_NavEKF2/AP_NavEKF2_core.h b/libraries/AP_NavEKF2/AP_NavEKF2_core.h index dad9bca384..5cac261b76 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2_core.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2_core.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* 24 state EKF based on https://github.com/priseborough/InertialNav diff --git a/libraries/AP_NavEKF2/AP_NavEKF_GyroBias.cpp b/libraries/AP_NavEKF2/AP_NavEKF_GyroBias.cpp index dd94ccbd26..46090689e7 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF_GyroBias.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF_GyroBias.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #if HAL_CPU_CLASS >= HAL_CPU_CLASS_150 diff --git a/libraries/AP_Navigation/AP_Navigation.h b/libraries/AP_Navigation/AP_Navigation.h index 285731732a..e46ec0a310 100644 --- a/libraries/AP_Navigation/AP_Navigation.h +++ b/libraries/AP_Navigation/AP_Navigation.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_Navigation.h /// @brief generic navigation controller interface diff --git a/libraries/AP_Notify/AP_BoardLED.cpp b/libraries/AP_Notify/AP_BoardLED.cpp index 2e9b931444..ec7782795a 100644 --- a/libraries/AP_Notify/AP_BoardLED.cpp +++ b/libraries/AP_Notify/AP_BoardLED.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Notify/AP_BoardLED.h b/libraries/AP_Notify/AP_BoardLED.h index 42843044ee..7de41286ff 100644 --- a/libraries/AP_Notify/AP_BoardLED.h +++ b/libraries/AP_Notify/AP_BoardLED.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Notify/AP_Notify.cpp b/libraries/AP_Notify/AP_Notify.cpp index 1948577c76..adc83cf9bd 100644 --- a/libraries/AP_Notify/AP_Notify.cpp +++ b/libraries/AP_Notify/AP_Notify.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Notify/AP_Notify.h b/libraries/AP_Notify/AP_Notify.h index 470d42703c..80ee4f9afc 100644 --- a/libraries/AP_Notify/AP_Notify.h +++ b/libraries/AP_Notify/AP_Notify.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Notify/Display.cpp b/libraries/AP_Notify/Display.cpp index 9c208afdac..3480887dee 100644 --- a/libraries/AP_Notify/Display.cpp +++ b/libraries/AP_Notify/Display.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Notify/Display.h b/libraries/AP_Notify/Display.h index 047b76af83..0172fd8212 100644 --- a/libraries/AP_Notify/Display.h +++ b/libraries/AP_Notify/Display.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "NotifyDevice.h" diff --git a/libraries/AP_Notify/Display_SSD1306_I2C.cpp b/libraries/AP_Notify/Display_SSD1306_I2C.cpp index da1c269582..502800367c 100644 --- a/libraries/AP_Notify/Display_SSD1306_I2C.cpp +++ b/libraries/AP_Notify/Display_SSD1306_I2C.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Notify/Display_SSD1306_I2C.h b/libraries/AP_Notify/Display_SSD1306_I2C.h index f93a3e13dc..a1c4dd4fbf 100644 --- a/libraries/AP_Notify/Display_SSD1306_I2C.h +++ b/libraries/AP_Notify/Display_SSD1306_I2C.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "Display.h" diff --git a/libraries/AP_Notify/ExternalLED.cpp b/libraries/AP_Notify/ExternalLED.cpp index ec9efeabdf..6740016d81 100644 --- a/libraries/AP_Notify/ExternalLED.cpp +++ b/libraries/AP_Notify/ExternalLED.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Notify/ExternalLED.h b/libraries/AP_Notify/ExternalLED.h index 36fc44f8bb..e6fc7eac26 100644 --- a/libraries/AP_Notify/ExternalLED.h +++ b/libraries/AP_Notify/ExternalLED.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Notify/RCOutputRGBLed.cpp b/libraries/AP_Notify/RCOutputRGBLed.cpp index 0d31223b57..40dca110fe 100644 --- a/libraries/AP_Notify/RCOutputRGBLed.cpp +++ b/libraries/AP_Notify/RCOutputRGBLed.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Copyright (C) 2015 Intel Corporation. All rights reserved. * diff --git a/libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp b/libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp index 0de3e4b0f1..2ceeb974eb 100644 --- a/libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp +++ b/libraries/AP_Notify/examples/ToshibaLED_test/ToshibaLED_test.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- - #include #include diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow.h b/libraries/AP_OpticalFlow/AP_OpticalFlow.h index 42f21f6903..ba56b0d5dc 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_OpticalFlow.h /// @brief Catch-all header that defines all supported optical flow classes. diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HIL.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_HIL.cpp index 4f0c00f21c..9497b3b03e 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HIL.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HIL.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_HIL.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_HIL.h index 1a58dd516b..5fb8b844b4 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_HIL.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_HIL.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "OpticalFlow.h" diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.cpp index b659a978da..2c26b0c7f7 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.h index 58e106cda1..ab71697e04 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_Linux.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* * Portions of this driver were borrowed from the PX4Firmware px4flow driver which can be found here: * https://github.com/PX4/Firmware/blob/master/src/drivers/px4flow/px4flow.cpp diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4.cpp b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4.cpp index 84c52f5b42..ba2cd79247 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4.cpp +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4.h b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4.h index 2f50a2c20c..a05235b9c8 100644 --- a/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4.h +++ b/libraries/AP_OpticalFlow/AP_OpticalFlow_PX4.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "OpticalFlow.h" diff --git a/libraries/AP_OpticalFlow/OpticalFlow.cpp b/libraries/AP_OpticalFlow/OpticalFlow.cpp index 7488b4cdbf..2687012e58 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow.cpp +++ b/libraries/AP_OpticalFlow/OpticalFlow.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "OpticalFlow.h" #include "AP_OpticalFlow_Onboard.h" diff --git a/libraries/AP_OpticalFlow/OpticalFlow_backend.cpp b/libraries/AP_OpticalFlow/OpticalFlow_backend.cpp index b9bb708bba..af167953de 100644 --- a/libraries/AP_OpticalFlow/OpticalFlow_backend.cpp +++ b/libraries/AP_OpticalFlow/OpticalFlow_backend.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Parachute/AP_Parachute.cpp b/libraries/AP_Parachute/AP_Parachute.cpp index 0934df9155..6c7da359a5 100644 --- a/libraries/AP_Parachute/AP_Parachute.cpp +++ b/libraries/AP_Parachute/AP_Parachute.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "AP_Parachute.h" #include #include diff --git a/libraries/AP_Parachute/AP_Parachute.h b/libraries/AP_Parachute/AP_Parachute.h index 545c7671ee..a015b2d53b 100644 --- a/libraries/AP_Parachute/AP_Parachute.h +++ b/libraries/AP_Parachute/AP_Parachute.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_Parachute.h /// @brief Parachute release library #pragma once diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index cfbca12f22..bc3600f70b 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Param/AP_Param.h b/libraries/AP_Param/AP_Param.h index 55ef29ed62..b2c5223d3c 100644 --- a/libraries/AP_Param/AP_Param.h +++ b/libraries/AP_Param/AP_Param.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index 0953f7ed02..c7effc4c0e 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/libraries/AP_Proximity/AP_Proximity.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Proximity/AP_Proximity.h b/libraries/AP_Proximity/AP_Proximity.h index 293ab991fa..c31e2677c4 100644 --- a/libraries/AP_Proximity/AP_Proximity.h +++ b/libraries/AP_Proximity/AP_Proximity.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Proximity/AP_Proximity_Backend.cpp b/libraries/AP_Proximity/AP_Proximity_Backend.cpp index 205950728d..a3053aeb5a 100644 --- a/libraries/AP_Proximity/AP_Proximity_Backend.cpp +++ b/libraries/AP_Proximity/AP_Proximity_Backend.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Proximity/AP_Proximity_Backend.h b/libraries/AP_Proximity/AP_Proximity_Backend.h index 0879f46332..3d2ef68fe6 100644 --- a/libraries/AP_Proximity/AP_Proximity_Backend.h +++ b/libraries/AP_Proximity/AP_Proximity_Backend.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp index 546314264f..bd3ced15e6 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h index b9d804d64d..1b87b2f538 100644 --- a/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h +++ b/libraries/AP_Proximity/AP_Proximity_LightWareSF40C.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "AP_Proximity.h" diff --git a/libraries/AP_RCMapper/AP_RCMapper.cpp b/libraries/AP_RCMapper/AP_RCMapper.cpp index 31239e3f9c..f580803918 100644 --- a/libraries/AP_RCMapper/AP_RCMapper.cpp +++ b/libraries/AP_RCMapper/AP_RCMapper.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include "AP_RCMapper.h" diff --git a/libraries/AP_RCMapper/AP_RCMapper.h b/libraries/AP_RCMapper/AP_RCMapper.h index 2bae2d6c63..77182be947 100644 --- a/libraries/AP_RCMapper/AP_RCMapper.h +++ b/libraries/AP_RCMapper/AP_RCMapper.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include diff --git a/libraries/AP_RPM/AP_RPM.cpp b/libraries/AP_RPM/AP_RPM.cpp index 5175dd1719..328d1ff62f 100644 --- a/libraries/AP_RPM/AP_RPM.cpp +++ b/libraries/AP_RPM/AP_RPM.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RPM/AP_RPM.h b/libraries/AP_RPM/AP_RPM.h index 4f7fb6babd..d19ab38045 100644 --- a/libraries/AP_RPM/AP_RPM.h +++ b/libraries/AP_RPM/AP_RPM.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RPM/RPM_Backend.cpp b/libraries/AP_RPM/RPM_Backend.cpp index d2635f1b7a..37b628c40e 100644 --- a/libraries/AP_RPM/RPM_Backend.cpp +++ b/libraries/AP_RPM/RPM_Backend.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RPM/RPM_Backend.h b/libraries/AP_RPM/RPM_Backend.h index 6cea9fba19..11df1c1e21 100644 --- a/libraries/AP_RPM/RPM_Backend.h +++ b/libraries/AP_RPM/RPM_Backend.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RPM/RPM_PX4_PWM.cpp b/libraries/AP_RPM/RPM_PX4_PWM.cpp index 996728baa7..bb3bff88b3 100644 --- a/libraries/AP_RPM/RPM_PX4_PWM.cpp +++ b/libraries/AP_RPM/RPM_PX4_PWM.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RPM/RPM_PX4_PWM.h b/libraries/AP_RPM/RPM_PX4_PWM.h index 504c2eca56..125484c60b 100644 --- a/libraries/AP_RPM/RPM_PX4_PWM.h +++ b/libraries/AP_RPM/RPM_PX4_PWM.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RPM/RPM_SITL.cpp b/libraries/AP_RPM/RPM_SITL.cpp index c57d516615..884e5a7526 100644 --- a/libraries/AP_RPM/RPM_SITL.cpp +++ b/libraries/AP_RPM/RPM_SITL.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RPM/RPM_SITL.h b/libraries/AP_RPM/RPM_SITL.h index 4a94be62b1..c285dae773 100644 --- a/libraries/AP_RPM/RPM_SITL.h +++ b/libraries/AP_RPM/RPM_SITL.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp b/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp index bc57de1855..f6f76c8248 100644 --- a/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp +++ b/libraries/AP_RPM/examples/RPM_generic/RPM_generic.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RSSI/AP_RSSI.cpp b/libraries/AP_RSSI/AP_RSSI.cpp index 742eab037d..8d0b959776 100644 --- a/libraries/AP_RSSI/AP_RSSI.cpp +++ b/libraries/AP_RSSI/AP_RSSI.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RSSI/AP_RSSI.h b/libraries/AP_RSSI/AP_RSSI.h index a517f53d04..355ff3ec11 100644 --- a/libraries/AP_RSSI/AP_RSSI.h +++ b/libraries/AP_RSSI/AP_RSSI.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Rally/AP_Rally.cpp b/libraries/AP_Rally/AP_Rally.cpp index a810ab9348..9211ea9441 100644 --- a/libraries/AP_Rally/AP_Rally.cpp +++ b/libraries/AP_Rally/AP_Rally.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_Rally.h /// @brief Handles rally point storage and retrieval. #include "AP_Rally.h" diff --git a/libraries/AP_Rally/AP_Rally.h b/libraries/AP_Rally/AP_Rally.h index 20b6f4a002..ba9a20dd6c 100644 --- a/libraries/AP_Rally/AP_Rally.h +++ b/libraries/AP_Rally/AP_Rally.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_Rally.h /// @brief Handles rally point storage, retrieval and lookup diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.h b/libraries/AP_RangeFinder/AP_RangeFinder.h index f074af7d9a..1a82a490b3 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_RangeFinder.h /// @brief Catch-all header that defines all supported RangeFinder classes. diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp index 986e5b1335..dbcbfcb57a 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h index d08784c525..80da913833 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LeddarOne.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "RangeFinder.h" diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp index fbe7bde76c..38e68ea7e5 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h index ca655069e5..1f6e6a3faf 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareI2C.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "RangeFinder.h" diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp index 69d9f16206..018cec4da0 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h index fab118b5d1..d10716ae79 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_LightWareSerial.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "RangeFinder.h" diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp index a175cffc3b..b56298b33a 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h index 3c2e4cd88a..b847bc66cd 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MAVLink.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "RangeFinder.h" diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp index c2e02aeb9c..b7226abb38 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h index 4008c7e9de..d256742688 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarI2CXL.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "RangeFinder.h" diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PX4.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PX4.cpp index a68a77629c..d09197c714 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PX4.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PX4.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PX4.h b/libraries/AP_RangeFinder/AP_RangeFinder_PX4.h index e4058d10e7..4a7b9a5948 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PX4.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PX4.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.cpp index 526e6815a8..36946e17b9 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.h b/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.h index 131b760895..0fb131fa23 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PX4_PWM.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp index 750e4f635d..ffaff130f7 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h index 6438765258..3aa9351325 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_PulsedLightLRF.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "RangeFinder.h" diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp index 2e9eee3f8a..795c352f0f 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder_analog.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_analog.h b/libraries/AP_RangeFinder/AP_RangeFinder_analog.h index ac5edf3591..7251ee8e2e 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder_analog.h +++ b/libraries/AP_RangeFinder/AP_RangeFinder_analog.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- #pragma once #include "RangeFinder.h" diff --git a/libraries/AP_RangeFinder/RangeFinder.cpp b/libraries/AP_RangeFinder/RangeFinder.cpp index 9f450b99ff..8ea66036fd 100644 --- a/libraries/AP_RangeFinder/RangeFinder.cpp +++ b/libraries/AP_RangeFinder/RangeFinder.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/RangeFinder.h b/libraries/AP_RangeFinder/RangeFinder.h index 87bbab9246..9f46e9d7e8 100644 --- a/libraries/AP_RangeFinder/RangeFinder.h +++ b/libraries/AP_RangeFinder/RangeFinder.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/RangeFinder_Backend.cpp b/libraries/AP_RangeFinder/RangeFinder_Backend.cpp index b27253ac66..9af355163d 100644 --- a/libraries/AP_RangeFinder/RangeFinder_Backend.cpp +++ b/libraries/AP_RangeFinder/RangeFinder_Backend.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_RangeFinder/RangeFinder_Backend.h b/libraries/AP_RangeFinder/RangeFinder_Backend.h index edf8a57a2f..9fafa3fb7f 100644 --- a/libraries/AP_RangeFinder/RangeFinder_Backend.h +++ b/libraries/AP_RangeFinder/RangeFinder_Backend.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Relay/AP_Relay.cpp b/libraries/AP_Relay/AP_Relay.cpp index f3b26a7edc..6f246e51f7 100644 --- a/libraries/AP_Relay/AP_Relay.cpp +++ b/libraries/AP_Relay/AP_Relay.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* * AP_Relay.cpp * diff --git a/libraries/AP_Relay/AP_Relay.h b/libraries/AP_Relay/AP_Relay.h index a03121da75..bcaef0e1f8 100644 --- a/libraries/AP_Relay/AP_Relay.h +++ b/libraries/AP_Relay/AP_Relay.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* * AP_Relay.h * diff --git a/libraries/AP_Scheduler/AP_Scheduler.cpp b/libraries/AP_Scheduler/AP_Scheduler.cpp index 0b87fb8ce3..4d6e84a50a 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.cpp +++ b/libraries/AP_Scheduler/AP_Scheduler.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Scheduler/AP_Scheduler.h b/libraries/AP_Scheduler/AP_Scheduler.h index 1dfb671bca..216bcc040c 100644 --- a/libraries/AP_Scheduler/AP_Scheduler.h +++ b/libraries/AP_Scheduler/AP_Scheduler.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp index 29f5a8e5c7..7724c42b2d 100644 --- a/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp +++ b/libraries/AP_Scheduler/examples/Scheduler_test/Scheduler_test.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // // Simple test for the AP_Scheduler interface // diff --git a/libraries/AP_SerialManager/AP_SerialManager.cpp b/libraries/AP_SerialManager/AP_SerialManager.cpp index 5eae8ea527..f6bf1466e9 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.cpp +++ b/libraries/AP_SerialManager/AP_SerialManager.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* Please contribute your ideas! See http://dev.ardupilot.org for details diff --git a/libraries/AP_SerialManager/AP_SerialManager.h b/libraries/AP_SerialManager/AP_SerialManager.h index 3a1e14ce83..39e42dff61 100644 --- a/libraries/AP_SerialManager/AP_SerialManager.h +++ b/libraries/AP_SerialManager/AP_SerialManager.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* Please contribute your ideas! See http://dev.ardupilot.org for details diff --git a/libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp b/libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp index 0d68c8631e..a912223ab6 100644 --- a/libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp +++ b/libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.h b/libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.h index 1c5ef49a63..d9d957f1d6 100644 --- a/libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.h +++ b/libraries/AP_ServoRelayEvents/AP_ServoRelayEvents.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* * AP_ServoRelayEvent.h * diff --git a/libraries/AP_SpdHgtControl/AP_SpdHgtControl.h b/libraries/AP_SpdHgtControl/AP_SpdHgtControl.h index 319612d6e0..269b21120b 100644 --- a/libraries/AP_SpdHgtControl/AP_SpdHgtControl.h +++ b/libraries/AP_SpdHgtControl/AP_SpdHgtControl.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*- #pragma once /// @file AP_SpdHgtControl.h diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp index 9dd235ab3a..b7dbb3c358 100644 --- a/libraries/AP_TECS/AP_TECS.cpp +++ b/libraries/AP_TECS/AP_TECS.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "AP_TECS.h" #include diff --git a/libraries/AP_TECS/AP_TECS.h b/libraries/AP_TECS/AP_TECS.h index 1e3c9ed225..1b151f534d 100644 --- a/libraries/AP_TECS/AP_TECS.h +++ b/libraries/AP_TECS/AP_TECS.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file AP_TECS.h /// @brief Combined Total Energy Speed & Height Control. This is a instance of an /// AP_SpdHgtControl class diff --git a/libraries/AP_Terrain/AP_Terrain.cpp b/libraries/AP_Terrain/AP_Terrain.cpp index dafeb934eb..93e8229b20 100644 --- a/libraries/AP_Terrain/AP_Terrain.cpp +++ b/libraries/AP_Terrain/AP_Terrain.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Terrain/AP_Terrain.h b/libraries/AP_Terrain/AP_Terrain.h index b1704a55d0..00e88d21db 100644 --- a/libraries/AP_Terrain/AP_Terrain.h +++ b/libraries/AP_Terrain/AP_Terrain.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Terrain/TerrainGCS.cpp b/libraries/AP_Terrain/TerrainGCS.cpp index 922c4650ef..8c9834546a 100644 --- a/libraries/AP_Terrain/TerrainGCS.cpp +++ b/libraries/AP_Terrain/TerrainGCS.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Terrain/TerrainIO.cpp b/libraries/AP_Terrain/TerrainIO.cpp index ae6f31aab1..a6d6cbf080 100644 --- a/libraries/AP_Terrain/TerrainIO.cpp +++ b/libraries/AP_Terrain/TerrainIO.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Terrain/TerrainMission.cpp b/libraries/AP_Terrain/TerrainMission.cpp index 0f767c081d..15fd47a5b8 100644 --- a/libraries/AP_Terrain/TerrainMission.cpp +++ b/libraries/AP_Terrain/TerrainMission.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Terrain/TerrainUtil.cpp b/libraries/AP_Terrain/TerrainUtil.cpp index 7a855f2b9d..e006448288 100644 --- a/libraries/AP_Terrain/TerrainUtil.cpp +++ b/libraries/AP_Terrain/TerrainUtil.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/AP_Tuning/AP_Tuning.cpp b/libraries/AP_Tuning/AP_Tuning.cpp index 1ff6b2755d..bf8c737804 100644 --- a/libraries/AP_Tuning/AP_Tuning.cpp +++ b/libraries/AP_Tuning/AP_Tuning.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "AP_Tuning.h" #include diff --git a/libraries/AP_Tuning/AP_Tuning.h b/libraries/AP_Tuning/AP_Tuning.h index 59dd7b4c32..2c171c4e94 100644 --- a/libraries/AP_Tuning/AP_Tuning.h +++ b/libraries/AP_Tuning/AP_Tuning.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #pragma once #include diff --git a/libraries/DataFlash/DataFlash.h b/libraries/DataFlash/DataFlash.h index 594a4d5ff4..928109784d 100644 --- a/libraries/DataFlash/DataFlash.h +++ b/libraries/DataFlash/DataFlash.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* ************************************************************ */ /* Test for DataFlash Log library */ /* ************************************************************ */ diff --git a/libraries/DataFlash/DataFlash_Block.cpp b/libraries/DataFlash/DataFlash_Block.cpp index bec931240b..e8a011f68b 100644 --- a/libraries/DataFlash/DataFlash_Block.cpp +++ b/libraries/DataFlash/DataFlash_Block.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * DataFlash.cpp - DataFlash log library generic code */ diff --git a/libraries/DataFlash/DataFlash_Block.h b/libraries/DataFlash/DataFlash_Block.h index a630f13e87..e5ca25a0d0 100644 --- a/libraries/DataFlash/DataFlash_Block.h +++ b/libraries/DataFlash/DataFlash_Block.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* DataFlash logging - block oriented variant */ diff --git a/libraries/DataFlash/DataFlash_File.cpp b/libraries/DataFlash/DataFlash_File.cpp index 3c196d5a5b..dceb01b300 100644 --- a/libraries/DataFlash/DataFlash_File.cpp +++ b/libraries/DataFlash/DataFlash_File.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* DataFlash logging - file oriented variant diff --git a/libraries/DataFlash/DataFlash_File.h b/libraries/DataFlash/DataFlash_File.h index 6e228def84..ba22109ae4 100644 --- a/libraries/DataFlash/DataFlash_File.h +++ b/libraries/DataFlash/DataFlash_File.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* DataFlash logging - file oriented variant diff --git a/libraries/DataFlash/DataFlash_MAVLink.cpp b/libraries/DataFlash/DataFlash_MAVLink.cpp index 3a472e649f..2f7b7ea8c7 100644 --- a/libraries/DataFlash/DataFlash_MAVLink.cpp +++ b/libraries/DataFlash/DataFlash_MAVLink.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* DataFlash Remote(via MAVLink) logging */ diff --git a/libraries/DataFlash/DataFlash_MAVLink.h b/libraries/DataFlash/DataFlash_MAVLink.h index 28931eab47..967ef818fe 100644 --- a/libraries/DataFlash/DataFlash_MAVLink.h +++ b/libraries/DataFlash/DataFlash_MAVLink.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* DataFlash logging - MAVLink variant diff --git a/libraries/DataFlash/DataFlash_SITL.cpp b/libraries/DataFlash/DataFlash_SITL.cpp index a14bbfef10..d3990686f5 100644 --- a/libraries/DataFlash/DataFlash_SITL.cpp +++ b/libraries/DataFlash/DataFlash_SITL.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* hacked up DataFlash library for Desktop support */ diff --git a/libraries/DataFlash/LogFile.cpp b/libraries/DataFlash/LogFile.cpp index f6988907c6..332628041c 100644 --- a/libraries/DataFlash/LogFile.cpp +++ b/libraries/DataFlash/LogFile.cpp @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include #include diff --git a/libraries/DataFlash/examples/DataFlash_AllTypes/DataFlash_AllTypes.cpp b/libraries/DataFlash/examples/DataFlash_AllTypes/DataFlash_AllTypes.cpp index 3dcf03e9e6..9c5b8faeb9 100644 --- a/libraries/DataFlash/examples/DataFlash_AllTypes/DataFlash_AllTypes.cpp +++ b/libraries/DataFlash/examples/DataFlash_AllTypes/DataFlash_AllTypes.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Write out two logs, each containing samples of each attribute type */ diff --git a/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp b/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp index 53bfa244d3..72bea5400d 100644 --- a/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp +++ b/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* * Example of DataFlash library. * originally based on code by Jordi MuĂ’oz and Jose Julio diff --git a/libraries/Filter/AverageFilter.h b/libraries/Filter/AverageFilter.h index 25d816e082..931abf7ac0 100644 --- a/libraries/Filter/AverageFilter.h +++ b/libraries/Filter/AverageFilter.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/Filter/DerivativeFilter.cpp b/libraries/Filter/DerivativeFilter.cpp index 6a86f964ca..731c192ee0 100644 --- a/libraries/Filter/DerivativeFilter.cpp +++ b/libraries/Filter/DerivativeFilter.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/Filter/DerivativeFilter.h b/libraries/Filter/DerivativeFilter.h index 7aa5695cb5..ef3b0eb07c 100644 --- a/libraries/Filter/DerivativeFilter.h +++ b/libraries/Filter/DerivativeFilter.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/Filter/FilterClass.h b/libraries/Filter/FilterClass.h index 6e5ddea78f..1512c8a8a1 100644 --- a/libraries/Filter/FilterClass.h +++ b/libraries/Filter/FilterClass.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/Filter/FilterWithBuffer.h b/libraries/Filter/FilterWithBuffer.h index b463a95177..2a33791190 100644 --- a/libraries/Filter/FilterWithBuffer.h +++ b/libraries/Filter/FilterWithBuffer.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/Filter/LowPassFilter.h b/libraries/Filter/LowPassFilter.h index 13635572db..dffd006380 100644 --- a/libraries/Filter/LowPassFilter.h +++ b/libraries/Filter/LowPassFilter.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/Filter/LowPassFilter2p.h b/libraries/Filter/LowPassFilter2p.h index b2703a41d5..65ed7c8ba4 100644 --- a/libraries/Filter/LowPassFilter2p.h +++ b/libraries/Filter/LowPassFilter2p.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/Filter/ModeFilter.h b/libraries/Filter/ModeFilter.h index 90d61971e3..5c102932e1 100644 --- a/libraries/Filter/ModeFilter.h +++ b/libraries/Filter/ModeFilter.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/GCS_Console/examples/Console/Console.cpp b/libraries/GCS_Console/examples/Console/Console.cpp index 377dea5012..4d24505565 100644 --- a/libraries/GCS_Console/examples/Console/Console.cpp +++ b/libraries/GCS_Console/examples/Console/Console.cpp @@ -1,5 +1,3 @@ -// -*- Mode: C++; c-basic-offset: 8; indent-tabs-mode: nil -*- - // This code is placed into the public domain. #include diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index f8a2de4f3e..083becd0c6 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file GCS.h /// @brief Interface definition for the various Ground Control System // protocols. diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index a8e5e503ca..a9ca33874f 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* Common GCS MAVLink functions for all vehicle types diff --git a/libraries/GCS_MAVLink/GCS_Logs.cpp b/libraries/GCS_MAVLink/GCS_Logs.cpp index 668e9e5c67..f4319e5bd2 100644 --- a/libraries/GCS_MAVLink/GCS_Logs.cpp +++ b/libraries/GCS_MAVLink/GCS_Logs.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* MAVLink logfile transfer functions */ diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.cpp b/libraries/GCS_MAVLink/GCS_MAVLink.cpp index 4b129e484d..b8fffbc6e4 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.cpp +++ b/libraries/GCS_MAVLink/GCS_MAVLink.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/GCS_MAVLink/GCS_MAVLink.h b/libraries/GCS_MAVLink/GCS_MAVLink.h index 9edc94f397..754c84f98b 100644 --- a/libraries/GCS_MAVLink/GCS_MAVLink.h +++ b/libraries/GCS_MAVLink/GCS_MAVLink.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file GCS_MAVLink.h /// @brief One size fits all header for MAVLink integration. #pragma once diff --git a/libraries/GCS_MAVLink/GCS_Signing.cpp b/libraries/GCS_MAVLink/GCS_Signing.cpp index 7dd39852e5..1c5edd99e7 100644 --- a/libraries/GCS_MAVLink/GCS_Signing.cpp +++ b/libraries/GCS_MAVLink/GCS_Signing.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* Code for handling MAVLink2 signing diff --git a/libraries/GCS_MAVLink/GCS_serial_control.cpp b/libraries/GCS_MAVLink/GCS_serial_control.cpp index 35ef3e70b9..4f9d16a24f 100644 --- a/libraries/GCS_MAVLink/GCS_serial_control.cpp +++ b/libraries/GCS_MAVLink/GCS_serial_control.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* MAVLink SERIAL_CONTROL handling */ diff --git a/libraries/GCS_MAVLink/MAVLink_routing.cpp b/libraries/GCS_MAVLink/MAVLink_routing.cpp index 376dc39f53..1a5222e7de 100644 --- a/libraries/GCS_MAVLink/MAVLink_routing.cpp +++ b/libraries/GCS_MAVLink/MAVLink_routing.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/GCS_MAVLink/MAVLink_routing.h b/libraries/GCS_MAVLink/MAVLink_routing.h index 197cb28b76..07505a18db 100644 --- a/libraries/GCS_MAVLink/MAVLink_routing.h +++ b/libraries/GCS_MAVLink/MAVLink_routing.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file MAVLink_routing.h /// @brief handle routing of MAVLink packets by ID #pragma once diff --git a/libraries/GCS_MAVLink/examples/routing/routing.cpp b/libraries/GCS_MAVLink/examples/routing/routing.cpp index 9f828d7d4a..d4e9304dc5 100644 --- a/libraries/GCS_MAVLink/examples/routing/routing.cpp +++ b/libraries/GCS_MAVLink/examples/routing/routing.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // // Simple test for the GCS_MAVLink routing // diff --git a/libraries/PID/PID.cpp b/libraries/PID/PID.cpp index 9a98dd0ca6..a5a9942bec 100644 --- a/libraries/PID/PID.cpp +++ b/libraries/PID/PID.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file PID.cpp /// @brief Generic PID algorithm diff --git a/libraries/PID/PID.h b/libraries/PID/PID.h index b27def4b9d..139ca05104 100644 --- a/libraries/PID/PID.h +++ b/libraries/PID/PID.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file PID.h /// @brief Generic PID algorithm, with EEPROM-backed storage of constants. #pragma once diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 5ebdc584c1..012196eccd 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index bb40a00aa4..dd214bf455 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file RC_Channel.h /// @brief RC_Channel manager, with EEPROM-backed storage of constants. #pragma once diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index 28a434d897..184a732ff8 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #include "RC_Channel_aux.h" #include diff --git a/libraries/RC_Channel/RC_Channel_aux.h b/libraries/RC_Channel/RC_Channel_aux.h index aa086b36d4..d5020ddb3d 100644 --- a/libraries/RC_Channel/RC_Channel_aux.h +++ b/libraries/RC_Channel/RC_Channel_aux.h @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - /// @file RC_Channel_aux.h /// @brief RC_Channel manager for auxiliary channels (5..8), with EEPROM-backed storage of constants. /// @author Amilcar Lucas diff --git a/libraries/RC_Channel/SRV_Channel.cpp b/libraries/RC_Channel/SRV_Channel.cpp index e6f421652a..8adf8b693d 100644 --- a/libraries/RC_Channel/SRV_Channel.cpp +++ b/libraries/RC_Channel/SRV_Channel.cpp @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/RC_Channel/SRV_Channel.h b/libraries/RC_Channel/SRV_Channel.h index 2700cfd94e..775d33b516 100644 --- a/libraries/RC_Channel/SRV_Channel.h +++ b/libraries/RC_Channel/SRV_Channel.h @@ -1,4 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* control of servo output ranges, trim and servo reversal. This can optionally be used to provide separation of input and output channel diff --git a/libraries/SITL/SIM_ADSB.cpp b/libraries/SITL/SIM_ADSB.cpp index 48bbc8f5fc..ba6e916116 100644 --- a/libraries/SITL/SIM_ADSB.cpp +++ b/libraries/SITL/SIM_ADSB.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_ADSB.h b/libraries/SITL/SIM_ADSB.h index 45fd00b669..6dc3627ad6 100644 --- a/libraries/SITL/SIM_ADSB.h +++ b/libraries/SITL/SIM_ADSB.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Aircraft.cpp b/libraries/SITL/SIM_Aircraft.cpp index af64dae0af..dc3f7fc66d 100644 --- a/libraries/SITL/SIM_Aircraft.cpp +++ b/libraries/SITL/SIM_Aircraft.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Aircraft.h b/libraries/SITL/SIM_Aircraft.h index 5119deb9df..45ae0d9350 100644 --- a/libraries/SITL/SIM_Aircraft.h +++ b/libraries/SITL/SIM_Aircraft.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Balloon.cpp b/libraries/SITL/SIM_Balloon.cpp index 844d8f91a3..847577f4dd 100644 --- a/libraries/SITL/SIM_Balloon.cpp +++ b/libraries/SITL/SIM_Balloon.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Balloon.h b/libraries/SITL/SIM_Balloon.h index ce99787bbf..3ddcaa185c 100644 --- a/libraries/SITL/SIM_Balloon.h +++ b/libraries/SITL/SIM_Balloon.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_CRRCSim.cpp b/libraries/SITL/SIM_CRRCSim.cpp index 0502668c00..f388d2a2fa 100644 --- a/libraries/SITL/SIM_CRRCSim.cpp +++ b/libraries/SITL/SIM_CRRCSim.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_CRRCSim.h b/libraries/SITL/SIM_CRRCSim.h index d894e4359b..17f30fc6a5 100644 --- a/libraries/SITL/SIM_CRRCSim.h +++ b/libraries/SITL/SIM_CRRCSim.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_FlightAxis.cpp b/libraries/SITL/SIM_FlightAxis.cpp index 72df004aa6..8e653d6707 100644 --- a/libraries/SITL/SIM_FlightAxis.cpp +++ b/libraries/SITL/SIM_FlightAxis.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_FlightAxis.h b/libraries/SITL/SIM_FlightAxis.h index a8f796d4af..aaf820771e 100644 --- a/libraries/SITL/SIM_FlightAxis.h +++ b/libraries/SITL/SIM_FlightAxis.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Frame.cpp b/libraries/SITL/SIM_Frame.cpp index 0f14138473..c547757a08 100644 --- a/libraries/SITL/SIM_Frame.cpp +++ b/libraries/SITL/SIM_Frame.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Frame.h b/libraries/SITL/SIM_Frame.h index 0323c262d6..fef650d239 100644 --- a/libraries/SITL/SIM_Frame.h +++ b/libraries/SITL/SIM_Frame.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Gazebo.cpp b/libraries/SITL/SIM_Gazebo.cpp index c49df8f457..2113f9742f 100644 --- a/libraries/SITL/SIM_Gazebo.cpp +++ b/libraries/SITL/SIM_Gazebo.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Gazebo.h b/libraries/SITL/SIM_Gazebo.h index b9368dc0be..6fd0a7785a 100644 --- a/libraries/SITL/SIM_Gazebo.h +++ b/libraries/SITL/SIM_Gazebo.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Gimbal.cpp b/libraries/SITL/SIM_Gimbal.cpp index 1c0d8cb49c..598fb2077f 100644 --- a/libraries/SITL/SIM_Gimbal.cpp +++ b/libraries/SITL/SIM_Gimbal.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Gimbal.h b/libraries/SITL/SIM_Gimbal.h index c0cebc8cbe..efb8fb2075 100644 --- a/libraries/SITL/SIM_Gimbal.h +++ b/libraries/SITL/SIM_Gimbal.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Helicopter.cpp b/libraries/SITL/SIM_Helicopter.cpp index f3514b9446..46fdc5212d 100644 --- a/libraries/SITL/SIM_Helicopter.cpp +++ b/libraries/SITL/SIM_Helicopter.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Helicopter.h b/libraries/SITL/SIM_Helicopter.h index cf5c8c0b10..856c1e02e5 100644 --- a/libraries/SITL/SIM_Helicopter.h +++ b/libraries/SITL/SIM_Helicopter.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_ICEngine.cpp b/libraries/SITL/SIM_ICEngine.cpp index 4217e48de9..0585ced374 100644 --- a/libraries/SITL/SIM_ICEngine.cpp +++ b/libraries/SITL/SIM_ICEngine.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_ICEngine.h b/libraries/SITL/SIM_ICEngine.h index 12d732f57e..2b4d03013b 100644 --- a/libraries/SITL/SIM_ICEngine.h +++ b/libraries/SITL/SIM_ICEngine.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_JSBSim.cpp b/libraries/SITL/SIM_JSBSim.cpp index ad4cdfe68f..e95808e1ee 100644 --- a/libraries/SITL/SIM_JSBSim.cpp +++ b/libraries/SITL/SIM_JSBSim.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_JSBSim.h b/libraries/SITL/SIM_JSBSim.h index 2bc6611803..21bc51157f 100644 --- a/libraries/SITL/SIM_JSBSim.h +++ b/libraries/SITL/SIM_JSBSim.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Motor.cpp b/libraries/SITL/SIM_Motor.cpp index 77f99d884d..c9326ba2f3 100644 --- a/libraries/SITL/SIM_Motor.cpp +++ b/libraries/SITL/SIM_Motor.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Motor.h b/libraries/SITL/SIM_Motor.h index 413f0e2159..b263123f48 100644 --- a/libraries/SITL/SIM_Motor.h +++ b/libraries/SITL/SIM_Motor.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Multicopter.cpp b/libraries/SITL/SIM_Multicopter.cpp index 5b307a6e69..78afb6da6b 100644 --- a/libraries/SITL/SIM_Multicopter.cpp +++ b/libraries/SITL/SIM_Multicopter.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Multicopter.h b/libraries/SITL/SIM_Multicopter.h index a24dc59e71..2d9c88c6fb 100644 --- a/libraries/SITL/SIM_Multicopter.h +++ b/libraries/SITL/SIM_Multicopter.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Plane.cpp b/libraries/SITL/SIM_Plane.cpp index cdd1f2e505..4f960ae71d 100644 --- a/libraries/SITL/SIM_Plane.cpp +++ b/libraries/SITL/SIM_Plane.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Plane.h b/libraries/SITL/SIM_Plane.h index 138d9c8386..e9909b3354 100644 --- a/libraries/SITL/SIM_Plane.h +++ b/libraries/SITL/SIM_Plane.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_QuadPlane.cpp b/libraries/SITL/SIM_QuadPlane.cpp index d25af72fa6..53c7e43edb 100644 --- a/libraries/SITL/SIM_QuadPlane.cpp +++ b/libraries/SITL/SIM_QuadPlane.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_QuadPlane.h b/libraries/SITL/SIM_QuadPlane.h index 0c5b793303..303b41ecaa 100644 --- a/libraries/SITL/SIM_QuadPlane.h +++ b/libraries/SITL/SIM_QuadPlane.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Rover.cpp b/libraries/SITL/SIM_Rover.cpp index c069b63ee1..d956dc6a5e 100644 --- a/libraries/SITL/SIM_Rover.cpp +++ b/libraries/SITL/SIM_Rover.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Rover.h b/libraries/SITL/SIM_Rover.h index 75e59687be..aba357d697 100644 --- a/libraries/SITL/SIM_Rover.h +++ b/libraries/SITL/SIM_Rover.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_SingleCopter.cpp b/libraries/SITL/SIM_SingleCopter.cpp index 6479e0bfda..50aa9f5fd3 100644 --- a/libraries/SITL/SIM_SingleCopter.cpp +++ b/libraries/SITL/SIM_SingleCopter.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_SingleCopter.h b/libraries/SITL/SIM_SingleCopter.h index f819ffc95d..00aee84550 100644 --- a/libraries/SITL/SIM_SingleCopter.h +++ b/libraries/SITL/SIM_SingleCopter.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Tracker.cpp b/libraries/SITL/SIM_Tracker.cpp index 9f19062dbe..c2391685e6 100644 --- a/libraries/SITL/SIM_Tracker.cpp +++ b/libraries/SITL/SIM_Tracker.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_Tracker.h b/libraries/SITL/SIM_Tracker.h index 4335742246..46c10c3e8f 100644 --- a/libraries/SITL/SIM_Tracker.h +++ b/libraries/SITL/SIM_Tracker.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_XPlane.cpp b/libraries/SITL/SIM_XPlane.cpp index 1da773d57c..e5b46b8491 100644 --- a/libraries/SITL/SIM_XPlane.cpp +++ b/libraries/SITL/SIM_XPlane.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_XPlane.h b/libraries/SITL/SIM_XPlane.h index 211820c497..693c94b245 100644 --- a/libraries/SITL/SIM_XPlane.h +++ b/libraries/SITL/SIM_XPlane.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_last_letter.cpp b/libraries/SITL/SIM_last_letter.cpp index 8eae029321..acf0b3699d 100644 --- a/libraries/SITL/SIM_last_letter.cpp +++ b/libraries/SITL/SIM_last_letter.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SIM_last_letter.h b/libraries/SITL/SIM_last_letter.h index ff619345ea..3a956a050f 100644 --- a/libraries/SITL/SIM_last_letter.h +++ b/libraries/SITL/SIM_last_letter.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SITL.cpp b/libraries/SITL/SITL.cpp index be312eadc5..a6bf6576a8 100644 --- a/libraries/SITL/SITL.cpp +++ b/libraries/SITL/SITL.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index b236db8794..5f01357d63 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -1,5 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - #pragma once #include diff --git a/libraries/StorageManager/StorageManager.cpp b/libraries/StorageManager/StorageManager.cpp index b79bb92fff..ba4fe44c3a 100644 --- a/libraries/StorageManager/StorageManager.cpp +++ b/libraries/StorageManager/StorageManager.cpp @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* Please contribute your ideas! See http://dev.ardupilot.org for details diff --git a/libraries/StorageManager/StorageManager.h b/libraries/StorageManager/StorageManager.h index 89b5718730..88b2a0cd90 100644 --- a/libraries/StorageManager/StorageManager.h +++ b/libraries/StorageManager/StorageManager.h @@ -1,4 +1,3 @@ -/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- /* Please contribute your ideas! See http://dev.ardupilot.org for details diff --git a/libraries/StorageManager/examples/StorageTest/StorageTest.cpp b/libraries/StorageManager/examples/StorageTest/StorageTest.cpp index bbf7b7da10..1af0bcd2b1 100644 --- a/libraries/StorageManager/examples/StorageTest/StorageTest.cpp +++ b/libraries/StorageManager/examples/StorageTest/StorageTest.cpp @@ -1,5 +1,3 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - // // Simple test for the StorageManager class //