mirror of https://github.com/ArduPilot/ardupilot
Sub: Remove mode header
This commit is contained in:
parent
8d60a34474
commit
4112fd1316
|
@ -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.
|
// 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
|
// If you used to define your CONFIG_APM_HARDWARE setting here, it is no longer
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
// HIL_MODE SELECTION
|
// HIL_MODE SELECTION
|
||||||
//
|
//
|
||||||
// Mavlink supports
|
// Mavlink supports
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// set_home_state - update home state
|
// set_home_state - update home state
|
||||||
|
|
|
@ -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
|
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
|
it under the terms of the GNU General Public License as published by
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// get_smoothing_gain - returns smoothing gain to be passed into attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw
|
// get_smoothing_gain - returns smoothing gain to be passed into attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
#include "version.h"
|
#include "version.h"
|
||||||
|
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
#include "version.h"
|
#include "version.h"
|
||||||
|
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_Common/AP_Common.h>
|
#include <AP_Common/AP_Common.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
|
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
|
it under the terms of the GNU General Public License as published by
|
||||||
|
|
|
@ -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
|
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
|
it under the terms of the GNU General Public License as published by
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
#ifdef USERHOOK_INIT
|
#ifdef USERHOOK_INIT
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
// user defined variables
|
// user defined variables
|
||||||
|
|
||||||
// example variables used in Wii camera testing - replace with your own
|
// example variables used in Wii camera testing - replace with your own
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// performs pre-arm checks. expects to be called at 1hz.
|
// performs pre-arm checks. expects to be called at 1hz.
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
void Sub::init_capabilities(void)
|
void Sub::init_capabilities(void)
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// start_command - this function will be called when the ap_mission lib wishes to start a new command
|
// start_command - this function will be called when the ap_mission lib wishes to start a new command
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
//
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
|
|
@ -1,4 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -1,4 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
#if AUTOTUNE_ENABLED == ENABLED
|
#if AUTOTUNE_ENABLED == ENABLED
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -1,4 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// manual_init - initialise manual controller
|
// manual_init - initialise manual controller
|
||||||
|
|
|
@ -1,4 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
// ArduSub position hold flight mode
|
// ArduSub position hold flight mode
|
||||||
// GPS required
|
// GPS required
|
||||||
// Jacob Walser August 2016
|
// Jacob Walser August 2016
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// stabilize_init - initialise stabilize controller
|
// stabilize_init - initialise stabilize controller
|
||||||
|
|
|
@ -1,4 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
// ArduSub transect flight mode
|
// ArduSub transect flight mode
|
||||||
// Sub follows a line according to current crosstrack error supplied by XTE NMEA sentence
|
// Sub follows a line according to current crosstrack error supplied by XTE NMEA sentence
|
||||||
// Requires GPS providing crosstrack error
|
// Requires GPS providing crosstrack error
|
||||||
|
|
|
@ -1,4 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
// ArduSub velocity hold flight mode
|
// ArduSub velocity hold flight mode
|
||||||
// Pilot adjusts desired forward and lateral body-frame velocities
|
// Pilot adjusts desired forward and lateral body-frame velocities
|
||||||
// Position controller maintains desired velocities
|
// Position controller maintains desired velocities
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// Code to detect a crash main ArduCopter code
|
// Code to detect a crash main ArduCopter code
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL_Boards.h>
|
#include <AP_HAL/AP_HAL_Boards.h>
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
/*****************************************************************************
|
/*****************************************************************************
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
void Sub::failsafe_battery_event(void)
|
void Sub::failsafe_battery_event(void)
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
//
|
//
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// Code to integrate AC_Fence library with main ArduCopter code
|
// Code to integrate AC_Fence library with main ArduCopter code
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// read_inertia - read inertia in from accelerometers
|
// read_inertia - read inertia in from accelerometers
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// Functions that will handle joystick/gamepad input
|
// Functions that will handle joystick/gamepad input
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
#define ARM_DELAY 20 // called at 10hz so 2 seconds
|
#define ARM_DELAY 20 // called at 10hz so 2 seconds
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// run_nav_updates - top level call for the autopilot
|
// run_nav_updates - top level call for the autopilot
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
//
|
//
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// position_vector.pde related utility functions
|
// position_vector.pde related utility functions
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
void Sub::init_barometer(bool full_calibration)
|
void Sub::init_barometer(bool full_calibration)
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
#if CLI_ENABLED == ENABLED
|
#if CLI_ENABLED == ENABLED
|
||||||
|
|
|
@ -1,4 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
// Jacob Walser: jacob@bluerobotics.com
|
// Jacob Walser: jacob@bluerobotics.com
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
#define CONTROL_SWITCH_DEBOUNCE_TIME_MS 200
|
#define CONTROL_SWITCH_DEBOUNCE_TIME_MS 200
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
#include "version.h"
|
#include "version.h"
|
||||||
|
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
// update terrain data
|
// update terrain data
|
||||||
|
|
|
@ -1,5 +1,3 @@
|
||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
||||||
#if CLI_ENABLED == ENABLED
|
#if CLI_ENABLED == ENABLED
|
||||||
|
|
|
@ -1,4 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
#if CH6_TUNE_ENABLED == ENABLED
|
#if CH6_TUNE_ENABLED == ENABLED
|
||||||
|
|
||||||
|
|
|
@ -1,4 +1,3 @@
|
||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
// Code by Rustom Jehangir: rusty@bluerobotics.com
|
// Code by Rustom Jehangir: rusty@bluerobotics.com
|
||||||
|
|
||||||
#include "Sub.h"
|
#include "Sub.h"
|
||||||
|
|
Loading…
Reference in New Issue