Sub: Remove mode header

This commit is contained in:
Jacob Walser 2017-02-06 13:56:05 -05:00 committed by Andrew Tridgell
parent 8d60a34474
commit 4112fd1316
56 changed files with 0 additions and 103 deletions

View File

@ -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

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
// HIL_MODE SELECTION
//
// Mavlink supports

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
#include "version.h"

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
#include "version.h"

View File

@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
/*

View File

@ -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>

View File

@ -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

View File

@ -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

View File

@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
#ifdef USERHOOK_INIT

View File

@ -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

View File

@ -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.

View File

@ -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)

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
/*

View File

@ -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

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
/*

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
//
#pragma once
//////////////////////////////////////////////////////////////////////////////

View File

@ -1,4 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"

View File

@ -1,4 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"

View File

@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
/*

View File

@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
#if AUTOTUNE_ENABLED == ENABLED

View File

@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
/*

View File

@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
/*

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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

View File

@ -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>

View File

@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
/**

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
/*****************************************************************************

View File

@ -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)

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
//

View File

@ -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

View File

@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
/*

View File

@ -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

View File

@ -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

View File

@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
/*

View File

@ -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

View File

@ -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

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
//

View File

@ -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

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"

View File

@ -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)

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
#if CLI_ENABLED == ENABLED

View File

@ -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"

View File

@ -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

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
#include "version.h"

View File

@ -1,5 +1,3 @@
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
// update terrain data

View File

@ -1,5 +1,3 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
#include "Sub.h"
#if CLI_ENABLED == ENABLED

View File

@ -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

View File

@ -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"