Skip to content

Commit

Permalink
Sub: Remove mode header
Browse files Browse the repository at this point in the history
  • Loading branch information
jaxxzer authored and tridge committed Feb 21, 2017
1 parent 8d60a34 commit 4112fd1
Show file tree
Hide file tree
Showing 56 changed files with 0 additions and 103 deletions.
2 changes: 0 additions & 2 deletions ArduSub/APM_Config.h
Original file line number Diff line number Diff line change
@@ -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
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/APM_Config_mavlink_hil.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

// HIL_MODE SELECTION
//
// Mavlink supports
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/AP_State.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

// set_home_state - update home state
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/ArduSub.cpp
Original file line number Diff line number Diff line change
@@ -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
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/Attitude.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

// get_smoothing_gain - returns smoothing gain to be passed into attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/GCS_Mavlink.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"
#include "version.h"

Expand Down
2 changes: 0 additions & 2 deletions ArduSub/Log.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"
#include "version.h"

Expand Down
2 changes: 0 additions & 2 deletions ArduSub/Parameters.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

/*
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/Parameters.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#pragma once

#include <AP_Common/AP_Common.h>
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/Sub.cpp
Original file line number Diff line number Diff line change
@@ -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
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/Sub.h
Original file line number Diff line number Diff line change
@@ -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
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/UserCode.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

#ifdef USERHOOK_INIT
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/UserVariables.h
Original file line number Diff line number Diff line change
@@ -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
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/arming_checks.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

// performs pre-arm checks. expects to be called at 1hz.
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/capabilities.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

void Sub::init_capabilities(void)
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/commands.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

/*
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/commands_logic.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

// start_command - this function will be called when the ap_mission lib wishes to start a new command
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/compassmot.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

/*
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/config.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
//
#pragma once

//////////////////////////////////////////////////////////////////////////////
Expand Down
1 change: 0 additions & 1 deletion ArduSub/control_acro.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"


Expand Down
1 change: 0 additions & 1 deletion ArduSub/control_althold.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"


Expand Down
2 changes: 0 additions & 2 deletions ArduSub/control_auto.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

/*
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/control_autotune.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

#if AUTOTUNE_ENABLED == ENABLED
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/control_circle.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

/*
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/control_guided.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

/*
Expand Down
1 change: 0 additions & 1 deletion ArduSub/control_manual.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"

// manual_init - initialise manual controller
Expand Down
1 change: 0 additions & 1 deletion ArduSub/control_poshold.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// ArduSub position hold flight mode
// GPS required
// Jacob Walser August 2016
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/control_stabilize.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

// stabilize_init - initialise stabilize controller
Expand Down
1 change: 0 additions & 1 deletion ArduSub/control_transect.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// ArduSub transect flight mode
// Sub follows a line according to current crosstrack error supplied by XTE NMEA sentence
// Requires GPS providing crosstrack error
Expand Down
1 change: 0 additions & 1 deletion ArduSub/control_velhold.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// ArduSub velocity hold flight mode
// Pilot adjusts desired forward and lateral body-frame velocities
// Position controller maintains desired velocities
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/crash_check.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

// Code to detect a crash main ArduCopter code
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/defines.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#pragma once

#include <AP_HAL/AP_HAL_Boards.h>
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/ekf_check.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

/**
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/esc_calibration.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

/*****************************************************************************
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/events.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

void Sub::failsafe_battery_event(void)
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/failsafe.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

//
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/fence.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

// Code to integrate AC_Fence library with main ArduCopter code
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/flight_mode.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

/*
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/inertia.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

// read_inertia - read inertia in from accelerometers
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/joystick.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

// Functions that will handle joystick/gamepad input
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/leds.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"


Expand Down
2 changes: 0 additions & 2 deletions ArduSub/motor_test.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

/*
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/motors.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

#define ARM_DELAY 20 // called at 10hz so 2 seconds
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/navigation.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

// run_nav_updates - top level call for the autopilot
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/perf_info.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

//
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/position_vector.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

// position_vector.pde related utility functions
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/radio.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"


Expand Down
2 changes: 0 additions & 2 deletions ArduSub/sensors.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

void Sub::init_barometer(bool full_calibration)
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/setup.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

#if CLI_ENABLED == ENABLED
Expand Down
1 change: 0 additions & 1 deletion ArduSub/surface_bottom_detector.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// Jacob Walser: jacob@bluerobotics.com

#include "Sub.h"
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/switches.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

#define CONTROL_SWITCH_DEBOUNCE_TIME_MS 200
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/system.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"
#include "version.h"

Expand Down
2 changes: 0 additions & 2 deletions ArduSub/terrain.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

// update terrain data
Expand Down
2 changes: 0 additions & 2 deletions ArduSub/test.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-

#include "Sub.h"

#if CLI_ENABLED == ENABLED
Expand Down
1 change: 0 additions & 1 deletion ArduSub/tuning.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
#if CH6_TUNE_ENABLED == ENABLED

Expand Down
1 change: 0 additions & 1 deletion ArduSub/turn_counter.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// Code by Rustom Jehangir: rusty@bluerobotics.com

#include "Sub.h"
Expand Down

0 comments on commit 4112fd1

Please sign in to comment.