mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
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.
This commit is contained in:
parent
53d3a799e7
commit
152edf7189
@ -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
|
// 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.
|
// their default values, place the appropriate #define statements here.
|
||||||
|
|
||||||
|
@ -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 "Rover.h"
|
#include "Rover.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 "Rover.h"
|
#include "Rover.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 "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,4 +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,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
|
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,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
|
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 "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
/*****************************************
|
/*****************************************
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
void Rover::init_capabilities(void)
|
void Rover::init_capabilities(void)
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
/* Functions in this file:
|
/* Functions in this file:
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
/********************************************************************************/
|
/********************************************************************************/
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
// called by update navigation at 10Hz
|
// called by update navigation at 10Hz
|
||||||
|
@ -1,4 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
//
|
//
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
void Rover::read_control_switch()
|
void Rover::read_control_switch()
|
||||||
|
@ -1,4 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
// Internal defines, don't edit and expect things to work
|
// Internal defines, don't edit and expect things to work
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
void Rover::update_events(void)
|
void Rover::update_events(void)
|
||||||
|
@ -1,4 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
/*
|
/*
|
||||||
failsafe support
|
failsafe support
|
||||||
Andrew Tridgell, December 2011
|
Andrew Tridgell, December 2011
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
//****************************************************************
|
//****************************************************************
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
void Rover::init_barometer(bool full_calibration)
|
void Rover::init_barometer(bool full_calibration)
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Rover.h"
|
#include "Rover.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 -*-
|
|
||||||
/*****************************************************************************
|
/*****************************************************************************
|
||||||
The init_ardupilot function processes everything we need for an in - air restart
|
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
|
We will determine later if we are actually on the ground and process a
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Rover.h"
|
#include "Rover.h"
|
||||||
|
|
||||||
#if CLI_ENABLED == ENABLED
|
#if CLI_ENABLED == ENABLED
|
||||||
|
@ -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
|
// This file is just a placeholder for your configuration file. If
|
||||||
// you wish to change any of the setup parameters from their default
|
// you wish to change any of the setup parameters from their default
|
||||||
// values, place the appropriate #define statements here.
|
// values, place the appropriate #define statements here.
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
Lead developers: Matthew Ridley and Andrew Tridgell
|
Lead developers: Matthew Ridley and Andrew Tridgell
|
||||||
|
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "GCS_Mavlink.h"
|
#include "GCS_Mavlink.h"
|
||||||
|
|
||||||
#include "Tracker.h"
|
#include "Tracker.h"
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Tracker.h"
|
#include "Tracker.h"
|
||||||
|
|
||||||
#if LOGGING_ENABLED == ENABLED
|
#if LOGGING_ENABLED == ENABLED
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Tracker.h"
|
#include "Tracker.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,4 +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 -*-
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
Lead developers: Matthew Ridley and Andrew Tridgell
|
Lead developers: Matthew Ridley and Andrew Tridgell
|
||||||
|
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Tracker.h"
|
#include "Tracker.h"
|
||||||
|
|
||||||
void Tracker::init_capabilities(void)
|
void Tracker::init_capabilities(void)
|
||||||
|
@ -1,4 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
//
|
//
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Tracker.h"
|
#include "Tracker.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Tracker.h"
|
#include "Tracker.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Tracker.h"
|
#include "Tracker.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Tracker.h"
|
#include "Tracker.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,4 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
// Command/Waypoint/Location Options Bitmask
|
// Command/Waypoint/Location Options Bitmask
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Tracker.h"
|
#include "Tracker.h"
|
||||||
|
|
||||||
// Functions to read the RC radio input
|
// Functions to read the RC radio input
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Tracker.h"
|
#include "Tracker.h"
|
||||||
|
|
||||||
void Tracker::init_barometer(bool full_calibration)
|
void Tracker::init_barometer(bool full_calibration)
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Tracker.h"
|
#include "Tracker.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Tracker.h"
|
#include "Tracker.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 "Tracker.h"
|
#include "Tracker.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.
|
// 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,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
|
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,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
|
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 "Copter.h"
|
#include "Copter.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 "Copter.h"
|
#include "Copter.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 -*-
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
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,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
|
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 "Copter.h"
|
#include "Copter.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 "Copter.h"
|
#include "Copter.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 "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,4 +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 -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.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 -*-
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
copter specific AP_AdvancedFailsafe class
|
copter specific AP_AdvancedFailsafe class
|
||||||
*/
|
*/
|
||||||
|
@ -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
|
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 "Copter.h"
|
#include "Copter.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 "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
void Copter::update_ground_effect_detector(void)
|
void Copter::update_ground_effect_detector(void)
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
void Copter::init_capabilities(void)
|
void Copter::init_capabilities(void)
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.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 "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,4 +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 "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
|
|
||||||
|
@ -1,4 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
|
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.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 "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
static bool land_with_gps;
|
static bool land_with_gps;
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
#if POSHOLD_ENABLED == ENABLED
|
#if POSHOLD_ENABLED == ENABLED
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
|
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
// Code to detect a crash main ArduCopter code
|
// Code to detect a crash main ArduCopter code
|
||||||
|
@ -1,4 +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 "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*****************************************************************************
|
/*****************************************************************************
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
//
|
//
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.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 "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
// Traditional helicopter variables and functions
|
// Traditional helicopter variables and functions
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.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 "Copter.h"
|
#include "Copter.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 -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
|
|
||||||
|
@ -1,5 +1,3 @@
|
|||||||
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
||||||
|
|
||||||
#include "Copter.h"
|
#include "Copter.h"
|
||||||
|
|
||||||
|
|
||||||
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user